Subversion Repositories svnkaklik

Compare Revisions

Problem with comparison.

Ignore whitespace Rev HEAD → Rev 288

/roboti/istrobot/camerus/DOC/Camerus.doc
Cannot display: file marked as a binary type.
svn:mime-type = application/octet-stream
Property changes:
Added: svn:mime-type
+application/octet-stream
\ No newline at end of property
/roboti/istrobot/camerus/DOC/CAMERUS.DSN
Cannot display: file marked as a binary type.
svn:mime-type = application/octet-stream
Property changes:
Added: svn:mime-type
+application/octet-stream
\ No newline at end of property
/roboti/istrobot/camerus/DOC/prevodovky/prevodovka.fcb
0,0 → 1,137
G90 G40
 
M40
M6 T1
M3 S6000
 
 
 
G0 X0Y0 Z2.5
G1 Z-3.4 F100.0
G0 Z50.
X12.49 Y-10.
Z2.5
G1 Z-3.4
G0 Z50.
X21 Y-25.4
Z2.5
G1 Z-3.4
G0 Z50.
X12.49
Z2.5
G1 Z-3.4
G0 Z50.
X4
Z2.5
G1 Z-3.4
G0 Z50.
M30
M9
M6 T2
M3 S6000
G0 X-3.071 Y-10.594
G0 Z2.5
G1 Z0 F100.0
X-7.035 Y-11.131 Z-0.5
X-5.053 Y-10.863
X-3.071 Y-10.594
G2 X-1.383 Y-11.879 I-2.87 J-12.081
G1 X0.599 Y-26.511 F200.0
G3 X24.381 I12.49 J-24.9
G1 X26.363 Y-11.879
G3 X4.84 Y1.725 I12.49 J-10.
G2 X3.435 Y2.05 I4.293 J2.563
G3 X-1.249 Y-3.8 I0 J0
G2 X-0.625 Y-5.1 I-1.561 J-4.75
G3 X-1.383 Y-11.879 I12.49 J-10.
G2 X-2.668 Y-13.567 I-2.87 J-12.081 F100.0
G1 X-3.071 Y-10.594 F200.0
X-7.035 Y-11.131 Z-1. F100.0
X-5.053 Y-10.863
X-3.071 Y-10.594
G2 X-1.383 Y-11.879 I-2.87 J-12.081
G1 X0.599 Y-26.511 F200.0
G3 X24.381 I12.49 J-24.9
G1 X26.363 Y-11.879
G3 X4.84 Y1.725 I12.49 J-10.
G2 X3.435 Y2.05 I4.293 J2.563
G3 X-1.249 Y-3.8 I0 J0
G2 X-0.625 Y-5.1 I-1.561 J-4.75
G3 X-1.383 Y-11.879 I12.49 J-10.
G2 X-2.668 Y-13.567 I-2.87 J-12.081 F100.0
G1 X-3.071 Y-10.594 F200.0
X-7.035 Y-11.131 Z-1.5 F100.0
X-5.053 Y-10.863
X-3.071 Y-10.594
G2 X-1.383 Y-11.879 I-2.87 J-12.081
G1 X0.599 Y-26.511 F200.0
G3 X24.381 I12.49 J-24.9
G1 X26.363 Y-11.879
G3 X4.84 Y1.725 I12.49 J-10.
G2 X3.435 Y2.05 I4.293 J2.563
G3 X-1.249 Y-3.8 I0 J0
G2 X-0.625 Y-5.1 I-1.561 J-4.75
G3 X-1.383 Y-11.879 I12.49 J-10.
G2 X-2.668 Y-13.567 I-2.87 J-12.081 F100.0
G1 X-3.071 Y-10.594 F200.0
X-7.035 Y-11.131 Z-2. F100.0
X-5.053 Y-10.863
X-3.071 Y-10.594
G2 X-1.383 Y-11.879 I-2.87 J-12.081
G1 X0.599 Y-26.511 F200.0
G3 X24.381 I12.49 J-24.9
G1 X26.363 Y-11.879
G3 X4.84 Y1.725 I12.49 J-10.
G2 X3.435 Y2.05 I4.293 J2.563
G3 X-1.249 Y-3.8 I0 J0
G2 X-0.625 Y-5.1 I-1.561 J-4.75
G3 X-1.383 Y-11.879 I12.49 J-10.
G2 X-2.668 Y-13.567 I-2.87 J-12.081 F100.0
G1 X-3.071 Y-10.594 F200.0
X-7.035 Y-11.131 Z-2.5 F100.0
X-5.053 Y-10.863
X-3.071 Y-10.594
G2 X-1.383 Y-11.879 I-2.87 J-12.081
G1 X0.599 Y-26.511 F200.0
G3 X24.381 I12.49 J-24.9
G1 X26.363 Y-11.879
G3 X4.84 Y1.725 I12.49 J-10.
G2 X3.435 Y2.05 I4.293 J2.563
G3 X-1.249 Y-3.8 I0 J0
G2 X-0.625 Y-5.1 I-1.561 J-4.75
G3 X-1.383 Y-11.879 I12.49 J-10.
G2 X-2.668 Y-13.567 I-2.87 J-12.081 F100.0
G1 X-3.071 Y-10.594 F200.0
X-7.035 Y-11.131 Z-3. F100.0
X-5.053 Y-10.863
X-3.071 Y-10.594
G2 X-1.383 Y-11.879 I-2.87 J-12.081
G1 X0.599 Y-26.511 F200.0
G3 X24.381 I12.49 J-24.9
G1 X26.363 Y-11.879
G3 X4.84 Y1.725 I12.49 J-10.
G2 X3.435 Y2.05 I4.293 J2.563
G3 X-1.249 Y-3.8 I0 J0
G2 X-0.625 Y-5.1 I-1.561 J-4.75
G3 X-1.383 Y-11.879 I12.49 J-10.
G2 X-2.668 Y-13.567 I-2.87 J-12.081 F100.0
G1 X-3.071 Y-10.594 F200.0
X-7.035 Y-11.131 Z-3.5 F100.0
X-5.053 Y-10.863
X-3.071 Y-10.594
G2 X-1.383 Y-11.879 I-2.87 J-12.081
G1 X0.599 Y-26.511 F200.0
G3 X24.381 I12.49 J-24.9
G1 X26.363 Y-11.879
G3 X4.84 Y1.725 I12.49 J-10.
G2 X3.435 Y2.05 I4.293 J2.563
G3 X-1.249 Y-3.8 I0 J0
G2 X-0.625 Y-5.1 I-1.561 J-4.75
G3 X-1.383 Y-11.879 I12.49 J-10.
G2 X-2.668 Y-13.567 I-2.87 J-12.081 F100.0
G0 z50
M6 T1
G0 X0 Y0 Z50
 
 
M30
/roboti/istrobot/camerus/DOC/prevodovky/README.txt
0,0 → 1,3
Pøevodovka 5:1 pro motor speed 300
 
Pøi zalepování ložisek je nutno dbát, aby ložisko v èele u motoru bylo na stranì motoru srovnáno s rovinou èela, jinak by docházelo k vyklánìní osy pøevodovky.
/roboti/istrobot/camerus/DOC/Fotky/P3110001.JPG
Cannot display: file marked as a binary type.
svn:mime-type = application/octet-stream
Property changes:
Added: svn:mime-type
+application/octet-stream
\ No newline at end of property
/roboti/istrobot/camerus/DOC/Fotky/P3110002.JPG
Cannot display: file marked as a binary type.
svn:mime-type = application/octet-stream
Property changes:
Added: svn:mime-type
+application/octet-stream
\ No newline at end of property
/roboti/istrobot/camerus/DOC/Fotky/P3110003.JPG
Cannot display: file marked as a binary type.
svn:mime-type = application/octet-stream
Property changes:
Added: svn:mime-type
+application/octet-stream
\ No newline at end of property
/roboti/istrobot/camerus/DOC/Fotky/P3110004.JPG
Cannot display: file marked as a binary type.
svn:mime-type = application/octet-stream
Property changes:
Added: svn:mime-type
+application/octet-stream
\ No newline at end of property
/roboti/istrobot/camerus/DOC/Fotky/P3180013.JPG
Cannot display: file marked as a binary type.
svn:mime-type = application/octet-stream
Property changes:
Added: svn:mime-type
+application/octet-stream
\ No newline at end of property
/roboti/istrobot/camerus/DOC/Fotky/P3180014.JPG
Cannot display: file marked as a binary type.
svn:mime-type = application/octet-stream
Property changes:
Added: svn:mime-type
+application/octet-stream
\ No newline at end of property
/roboti/istrobot/camerus/DOC/Fotky/P3180015.JPG
Cannot display: file marked as a binary type.
svn:mime-type = application/octet-stream
Property changes:
Added: svn:mime-type
+application/octet-stream
\ No newline at end of property
/roboti/istrobot/camerus/DOC/Fotky/P3180024.JPG
Cannot display: file marked as a binary type.
svn:mime-type = application/octet-stream
Property changes:
Added: svn:mime-type
+application/octet-stream
\ No newline at end of property
/roboti/istrobot/camerus/DOC/Fotky/P3180025.JPG
Cannot display: file marked as a binary type.
svn:mime-type = application/octet-stream
Property changes:
Added: svn:mime-type
+application/octet-stream
\ No newline at end of property
/roboti/istrobot/camerus/DOC/Fotky/P3180026.JPG
Cannot display: file marked as a binary type.
svn:mime-type = application/octet-stream
Property changes:
Added: svn:mime-type
+application/octet-stream
\ No newline at end of property
/roboti/istrobot/camerus/DOC/Fotky/P3180027.JPG
Cannot display: file marked as a binary type.
svn:mime-type = application/octet-stream
Property changes:
Added: svn:mime-type
+application/octet-stream
\ No newline at end of property
/roboti/istrobot/camerus/DOC/Fotky/P3180028.JPG
Cannot display: file marked as a binary type.
svn:mime-type = application/octet-stream
Property changes:
Added: svn:mime-type
+application/octet-stream
\ No newline at end of property
/roboti/istrobot/camerus/ToDo.txt
0,0 → 1,11
- Tlaèítko na vypnutí, pøípadnì (IRDA)
- vyrobit modul na oci
 
- Udìlat podsvìtlení, aby se robot líbil porotì.
+- modul s LED, nebo neosadit stabilizator do modulu LEDrobot
+
+- vymyslet postup kalibrace kamery (jak vizualizovat co kamera vidi)
+ - co pouzit LEDbar?
+
+- projit problemy lonske konstrukce
/roboti/istrobot/camerus/SW/876/camerus.c
0,0 → 1,657
//********* Robot Camerus pro IstRobot 2007 ************
//"$Id$"
//*****************************************************
 
#include ".\camerus.h"
 
#USE FAST_IO (C) // Brana C je ve FAST_IO modu, aby slo rychle cist z kamery
 
// Rychlostni konstanty
#define RR_CIHLA 50 // Rozumna rychlost pro objizdeni cihly
#define RR_PRERUSENI 50 // Rozumna rychlost pro priblizeni se k preruseni
#define BRZDNA_DRAHA 0x15 // Jak daleko pred problemem se zacne brzdit
#define TUHOS 100 // Jak dlouho se bude couvat po narazu na naraznik
#define ODODO_CIHLA 0xD0
#define ODODO_TUNEL 0xFFF
#define ODODO_PRERUSENI 0xFFF//0xB4
 
// Adresy IIC periferii
#define COMPAS_ADR 0xC0
#define CAMERA_ADR 0xDC
#define SONAR_ADR 0xE0
 
// A/D vstupy
#define RMAX 4 // AN4/RA5 - leve cidlo na vyjeti z cary
#define LMAX 3 // AN3/RA3 - prave cidlo na vyjeti z cary
#define CERVENA 2 // AN2/RA2 - cervene kroutitko
#define ZELENA 1 // AN1/RA0 - zelene kroutitko
#define MODRA 0 // AN0/RA1 - modre kroutitko
 
// I/O
#define HREF PIN_C5 // Signal HREF z kamery (v H po celou dobu radku)
#define PIX PIN_C6 // Vstup pro body z kamery (za trivstupim hradlem OR (dig. komparator))
#define SERVO PIN_B4 // Vystup na servo (1 az 2ms po cca 20ms (synchronizovano snimkovym kmitoctem))
#define MOT_L PIN_B5 // Smer otaceni leveho motoru; druhy pol je RC2
#define MOT_R PIN_B6 // Smer otaceni praveho motoru; druhy pol je RC1
#define MOT_1 PIN_C1 // PWM vystpy motoru
#define MOT_2 PIN_C2 //
#define DATA PIN_B2 // K modulu LEDbar data
#define CP PIN_B1 // K modulu LEDbar hodiny
//#define ODO PIN_C0 // Ze snimace z odometrie z praveho kola na TIMER1
// Jeden impuls je 31,25mm
#define IRRX !input(PIN_B0) // Vstup INT, generuje preruseni pri prekazce
#define IRTX PIN_B3 // Modulovani vysilaci IR LED na detekci prekazky
#define PROXIMITY PIN_C7 // Cidlo kratkeho dosahu na cihlu
#define BUMPER !input(PIN_A4) // Naraznik
 
#define CASMIN 6 // Rozsah radku snimace
#define CASMAX 192
#define CASAVR ((CASMAX+CASMIN) / 2)
 
#define EEMAX 255 // Konec EEPROM
#define MAXLOG 0x10 // Maximalni pocet zaznamu v logu
#if MAXLOG>(EEMAX/3)
#error Prekrocena velikost EEPROM
#endif
 
#define OFFSETO 0x9F //0x9F // Vystredeni serva pro objeti prekazky
 
#define THR 90 // Threshold pro UV cidla na caru
 
#byte INTCON = 0x0B // Interrupt configuration register
#bit GIE = INTCON.7
#bit PEIE = INTCON.6
#bit TMR0IE = INTCON.5
#bit INT0IE = INTCON.4
#bit RBIE = INTCON.3
#bit TMR0IF = INTCON.2
#bit INT0IF = INTCON.1
#bit RBIF = INTCON.0
 
enum stavy {start,rozjezd,jizda,cihla,pocihle,cil};
stavy stav; // Kde jsme na trati
int8 cas; // Cas hrany bila/cerna v radce
int8 stred; // Vystredeni kolecka
int16 odocounter; // Zaznamenani aktualniho stavu pocitadla odometrie
int16 last_log_odo; // Posledni stav odometrie poznamenany do logu
int16 last_log; // Cislo posledniho zaznamu v logu v EEPROM
int8 bb_h[MAXLOG]; // Cerna skrinka MSB
int8 bb_l[MAXLOG]; // Cerna skrinka LSB
int8 bb_f[MAXLOG]; // Cerna skrinka priznak (typ zaznamu)
int8 log; // Pocitadlo pro cernou skrinku
int8 rr; // Promenna na ulozeni Rozumne rychlost
int8 rrold;
int16 odo_preruseni, odo_cihla, odo_tunel; // Problemy na trati
 
// Zobrazeni jednoho byte na modulu LEDbar
inline void disp(int8 x)
{
int n;
 
for(n=0;n<=7;n++)
{
if (bit_test(x,0)) output_low(DATA); else output_high(DATA);
output_high(CP);
x>>=1;
output_low(CP);
}
}
 
// Blikani LEDbarem ve stilu Night Rider
void NightRider(int8 x)
{
int n,i,j;
 
for(j=0;j<x;j++)
{
i=0x01;
for(n=0;n<7;n++)
{
disp(i);
rotate_left(&i, 1);
delay_ms(40);
}
for(n=0;n<7;n++)
{
disp(i);
rotate_right(&i, 1);
delay_ms(40);
}
}
disp(i);
delay_ms(40);
i=0;
disp(i);
}
 
// Zaznam LOGu do EEPROM
void SaveLog()
{
int8 n,i,xlog;
 
i=0;
for(n=0;n<=(log*3);n+=3) // Ulozeni Black Boxu do EEPROM
{
write_eeprom(n,bb_f[i]);
write_eeprom(n+1,bb_h[i]);
write_eeprom(n+2,bb_l[i]);
i++;
};
if(log>0) {xlog=log-1;} else {xlog=0;};
write_eeprom(EEMAX,xlog); // Zapis poctu zaznamu na konec EEPROM
}
 
// Zaznam do Logu do RAM
void LogLog(int8 reason, int16 log_delay)
{
int16 timer_pom;
 
timer_pom=get_timer1(); // Timer se musi vycist atomicky
bb_l[log]=make8(timer_pom,0); // Zaznam
bb_h[log]=make8(timer_pom,1);
bb_f[log]=reason; // Typ zaznamu
if(log<(MAXLOG-1)) log++; // Ukazatel na dalsi zaznam
last_log_odo=timer_pom+log_delay; // Dalsi mereni nejdrive po ujeti def. vzdalenosti
rr=rrold; // Problem skoncil, znovu jed Rozumnou Rychlosti
}
 
void ReadBlackBox()
{
last_log=read_eeprom(EEMAX); // Kolik zaznamu mame od minule poznamenano?
{
int8 n,i;
 
i=0;
for(n=0;n<=last_log;n++)
{
if(read_eeprom(i)==0) odo_tunel=MAKE16(read_eeprom(i+2),read_eeprom(i+1));
if(read_eeprom(i)==0xFF) odo_cihla=MAKE16(read_eeprom(i+2),read_eeprom(i+1));
if((read_eeprom(i)>0) && (read_eeprom(i)<0xFF)) odo_preruseni=MAKE16(read_eeprom(i+2),read_eeprom(i+1));
}
}
}
 
 
// Brzdeni motorama stridou 1:1
void brzda()
{
int8 n,i;
 
set_pwm1_duty(0); // vypni PWM
set_pwm2_duty(0);
setup_ccp1(CCP_OFF);
setup_ccp2(CCP_OFF);
for (n=0;n<200;n++)
{
output_low(MOT_L);
output_low(MOT_R);
output_high(MOT_1);
output_high(MOT_2);
delay_us(200);
output_high(MOT_L);
output_high(MOT_R);
output_low(MOT_1);
output_low(MOT_2);
delay_us(200);
}
output_low(MOT_L); // smer vpred
output_low(MOT_R);
setup_ccp1(CCP_PWM); // RC1 // Zapni PWM pro motory
setup_ccp2(CCP_PWM); // RC2
}
 
void SetServo(int8 angle)
{
int8 n;
 
for(n=0; n<10; n++)
{
output_high(SERVO); // Odvysilani impuzu 1 az 2ms pro servo
delay_us(1000);
delay_us(stred);
delay_us(stred);
delay_us(stred);
delay_us(angle);
delay_us(angle);
output_low(SERVO);
delay_ms(18);
}
}
 
inline void SetServoQ(int8 angle)
{
output_high(SERVO); // Odvysilani impuzu 1 az 2ms pro servo
delay_us(1000);
delay_us(stred);
delay_us(stred);
delay_us(stred);
delay_us(angle);
delay_us(angle);
output_low(SERVO);
}
 
// Couvni po narazu na naraznik
inline void bum()
{
set_pwm1_duty(0); // couvni, rovne dozadu
set_pwm2_duty(0);
output_high(MOT_L);
output_high(MOT_R);
disp(0xA5);
SetServo(CASAVR-CASMIN);
}
 
#include ".\diag.c"
 
//---------------------------- INT --------------------------------
#int_EXT
EXT_isr() // Preruseni od prekazky
{
unsigned int8 bearing, bearing_offset, delta_bearing;
 
set_pwm1_duty(0); // zabrzdi levym kolem, prave vypni
set_pwm2_duty(0);
output_high(MOT_L);
output_low(MOT_R);
// Ujistime se, ze prijaty signal je z naseho IR vysilace
output_high(IRTX); // Vypni LED na detekci prekazky
delay_ms(2);
if (IRRX) // stale nas signal?
{
output_low(MOT_L); // je odraz -> vpred
output_low(MOT_R);
return;
};
output_low(IRTX); // Zapni LED na detekci prekazky
 
i2c_start(); // Cteni kompasu
i2c_write(COMPAS_ADR);
i2c_write(0x1); // 0-255 (odpovida 0-359)
i2c_stop();
i2c_start();
i2c_write(COMPAS_ADR+1);
bearing_offset=i2c_read(0); // Poznamenej hodnotu pred cihlou
i2c_stop();
 
delay_ms(9);
if (!IRRX) // stale nas signal?
{
output_low(MOT_L); // neni odraz -> vpred
output_low(MOT_R);
return;
};
 
rr=rrold; // Po cihle se pojede opet Rozumnou Rychlosti
if(stav!=cihla)
{
LogLog(0xFF,3); // Cihla
};
 
//!!! if(stav==cihla) while(true); // Zastav na furt, konec drahy
// if(stav==cihla) return; // Po druhe nic neobjizdej
// Pozor na rozjezd
 
if((stav==jizda)||(stav==cihla)) // Objed cihlu
{
#include ".\objizdka_L.c"
};
last_log_odo=get_timer1()+16; // Pul metru po cihle nezaznamenavej do LOGu
}
 
 
//---------------------------------- MAIN --------------------------------------
void main()
{
int8 offset; // Promena pro ulozeni offsetu
int8 r1; // Rychlost motoru 1
int8 r2; // Rychlost motoru 2
int16 ble;
 
setup_adc_ports(ALL_ANALOG); // Zapnuti A/D prevodniku pro cteni kroutitek
setup_adc(ADC_CLOCK_INTERNAL);
setup_timer_0(RTCC_INTERNAL|RTCC_DIV_1); // Casovac pro mereni casu hrany W/B v radce
setup_timer_1(T1_EXTERNAL); // Cita pulzy z odometrie z praveho kola
setup_timer_2(T2_DIV_BY_16,255,1); // Casovac PWM motoru
//!!! setup_timer_2(T2_DIV_BY_4,255,1); // Casovac PWM motoru
setup_ccp1(CCP_PWM); // RC1 // PWM pro motory
setup_ccp2(CCP_PWM); // RC2
setup_comparator(NC_NC_NC_NC);
setup_vref(FALSE);
 
set_tris_c(0b11111001); // Nastaveni vstup/vystup pro branu C, protoze se to nedela automaticky
 
set_pwm1_duty(0); // Zastav motory
set_pwm2_duty(0);
output_low(MOT_L); // Nastav smer vpred
output_low(MOT_R);
 
disp(0); // Zhasni LEDbar
 
if(BUMPER) // Kdyz nekdo na zacatku drzi naraznik, vymaz log a spust diagnostiku
{
diag();
}
 
output_low(IRTX); // Zapni LED na detekci prekazky
 
NightRider(1); // Zablikej, aby se poznalo, ze byl RESET
// Zaroven se musi pockat, nez se rozjede kamera, nez se do ni zacnou posilat prikazy
 
//... Nastaveni sonaru ...
i2c_start();
i2c_write(SONAR_ADR);
i2c_write(0x02); // dosah
i2c_write(0x03); // n*43mm
i2c_stop();
i2c_start();
i2c_write(SONAR_ADR);
i2c_write(0x01); // zesileni
i2c_write(0x01); // male, pro eliminaci echa z minuleho mereni
i2c_stop();
 
//... Nastaveni kamery ...
i2c_start(); // Soft RESET kamery
i2c_write(CAMERA_ADR); // Adresa kamery
i2c_write(0x12); // Adresa registru COMH
i2c_write(0x80 | 0x24); // Zapis ridiciho slova
i2c_stop();
 
i2c_start(); // BW
i2c_write(CAMERA_ADR);
i2c_write(0x28);
i2c_write(0b01000001);
i2c_stop();
 
/*
i2c_start(); // Contrast (nema podstatny vliv na obraz)
i2c_write(CAMERA_ADR);
i2c_write(0x05);
i2c_write(0xA0); // 48h
i2c_stop();
 
i2c_start(); // Band Filter (pokud by byl problem se zarivkama 50Hz)
i2c_write(CAMERA_ADR);
i2c_write(0x2D);
i2c_write(0x04 | 0x03);
i2c_stop();
*/
 
i2c_start(); // Fame Rate
i2c_write(CAMERA_ADR);
i2c_write(0x2B);
i2c_write(0x00); // cca 17ms (puvodni hodnota 5Eh = 20ms)
i2c_stop();
 
i2c_start(); // VSTRT
i2c_write(CAMERA_ADR);
i2c_write(0x19);
i2c_write(118); // prostredni radka
i2c_stop();
 
i2c_start(); // VEND
i2c_write(CAMERA_ADR);
i2c_write(0x1A);
i2c_write(118);
i2c_stop();
 
NightRider(1); // Musi se dat cas kamere na AGC a AEC
 
{ // Mereni expozice
int8 t1,t2;
 
i2c_start(); // Brightness, zacni od uplne tmy
i2c_write(CAMERA_ADR);
i2c_write(0x06);
i2c_write(0); // 80h default
i2c_stop();
delay_ms(50);
 
for(offset=0x04;offset<(255-0x04);offset+=0x04) // Zacni od jasu 10h
{
i2c_start(); // Brightness
i2c_write(CAMERA_ADR);
i2c_write(0x06);
i2c_write(offset); // 80h default
i2c_stop();
disp(offset);
delay_ms(50);
 
t1=0;
t2=0;
while(!input(HREF)); // Cekej nez se zacnou posilat pixely z radky
delay_ms(5);
while(!input(HREF)); // Cekej nez se zacnou posilat pixely z radky
set_timer0(0); // Vynuluj pocitadlo casu
if(!input(PIX)) continue;
while(input(PIX));
t1=get_timer0(); // Precti cas z citace casu hrany
set_timer0(0); // Vynuluj pocitadlo casu
while(!input(PIX));
t2=get_timer0();
 
if((t1>60) && (t1<140) && (t2>5) && (t2<=10)) break; // Vidis, co mas?
 
delay_ms(2); // Preskoc druhou radku z kamery
};
delay_ms(1000); // Nech chvili na displayi zmerenou hodnotu
}
 
set_adc_channel(CERVENA); // --- Kroutitko pro jas ---
delay_ms(1);
offset=read_adc();
offset &= 0b11111100; // Dva nejnizsi bity ignoruj
// offset += 0x70; // Jas nebude nikdy nizsi
disp(offset);
i2c_start(); // Brightness
i2c_write(CAMERA_adr);
i2c_write(0x06);
i2c_write(offset); // 80h default
i2c_stop();
delay_ms(1000); // Nech hodnotu chvili na displayi
 
set_adc_channel(ZELENA); // --- Kroutitko pro vykon motoru ---
delay_ms(1);
rr=read_adc()>>2; // 0-63 // Pokud by se zvetsil rozsah, tak zkontrolovat jakonasobeni!
rr+=27; // 27-90
//!!! rr=read_adc()>>1; // 0-128 // Pokud by se zvetsil rozsah, tak zkontrolovat jakonasobeni!
rrold=rr;
 
cas=CASAVR-CASMIN; // Inicializace promenych, aby neslo servo za roh
// a aby se to rozjelo jeste dneska
stav=start; // Jsme na startu
set_timer1(0); // Vynuluj citac odometrie
log=0; // Zacatek logu v cerne skrince
last_log_odo=0; // Posledni zaznam odometrie do logu
 
// ReadBlackBox(); // Vycteni zaznamu z Black Boxu
 
odo_cihla=ODODO_CIHLA-BRZDNA_DRAHA;
odo_tunel=ODODO_TUNEL-BRZDNA_DRAHA;
odo_preruseni=ODODO_PRERUSENI-BRZDNA_DRAHA;
 
// ........................... Hlavni smycka ................................
while(true)
{
int8 pom;
int8 n;
int8 gap;
int16 ododo;
 
gap=0; // Vynuluj pocitadlo preruseni
 
next_snap:
 
pom=0;
disable_interrupts(GLOBAL); //----------------------- Critical Section
while(input(HREF)); // Preskoc 1. radku
while(!input(HREF)); // Cekej nez se zacnou posilat pixely z 2. radky
set_timer0(0); // Vynuluj pocitadlo casu
while(input(HREF)) // Po dobu vysilani radky cekej na hranu W/B
{
// !!!!Dodelat rozpoznani cerne cary napric pro zastaveni ?
if(!input(PIX)) // Pokud se X-krat za sebou precetla CERNA
if(!input(PIX))
// if(!input(PIX))
{
pom=get_timer0(); // Precti cas z citace casu hrany
break;
};
};
while(input(HREF)); // Pockej na shozeni signalu HREF
 
if((pom<CASMAX) && (pom>CASMIN)) cas=pom; // Orizni konce radku
// Na konci obrazovaho radku to blbne. Jednak chyba od apertury
// a vubec to nejak na kraji nefunguje.
 
output_high(SERVO); // Odvysilani impuzu 1 az 2ms pro servo
delay_us(1000);
delay_us(stred);
delay_us(stred);
delay_us(stred);
delay_us(cas);
delay_us(cas);
output_low(SERVO);
 
// Elektronicky diferencial 1. cast
if(cas<CASAVR) {r1=cas-CASMIN; r2=CASAVR-CASMIN;}; // Normovani vystupni hodnoty radkoveho snimace
if(cas==CASAVR) {r1=cas-CASMIN; r2=cas-CASMIN;}; // pro rizeni rychlosti motoru
if(cas>CASAVR) {r1=CASAVR-CASMIN; r2=CASMAX-cas;}; // Rozsah 1 az 92
 
enable_interrupts(GLOBAL); //----------------------- End Critical Section
 
if(pom==0) // Kamera nevidi caru
{
if((cas>(CASMIN+15))&&(cas<(CASMAX-15))) // Nebyla minule cara moc u kraje?
{
gap++;
if(gap>=3) // Trva preruseni cary alespon 2 snimky?
{
cas=CASAVR-CASMIN;
// disp(0xAA);
}
}
}
else
{
gap=0;
};
 
 
/*
if(pom==0) // Kamera nevidi caru, poznamenej to do logu
{
if((cas>(CASMIN+30))&&(cas<(CASMAX-30))) // Nebyla minule cara moc u kraje?
if(last_log_odo<get_timer1()) // Aby nebyly zaznamy v logu prilis huste, musi se napred neco ujet od minuleho zaznamu
{
gap++;
}
}
else
{
if(gap>=4) // Trva preruseni cary alespon 2 snimky?
{
LogLog(gap,8); // Dalsi mereni nejdrive po ujeti 24 cm
rr=rrold; // Preruseni cary skoncilo, znovu jed Rozumnou Rychlosti
cas=CASAVR-CASMIN;
disp(0xAA);
}
gap=0;
};
 
if(!input(PROXIMITY) && ((stav==jizda)||(stav==cihla))) // Tunel
{
if(last_log_odo<get_timer1()) // Aby nebyly zaznamy v logu prilis huste, musi se napred neco ujet od minuleho zaznamu
{
LogLog(0xDD,16); // Priznak tunelu; dalsi mereni nejdrive po ujeti 48 cm
rr=rrold; // Vjeli jsme do tunelu, znovu jed rychle
}
};
*/
 
//ODODO
ododo=get_timer1();
if((ododo>odo_preruseni)&&(ododo<(odo_preruseni+8))) rr=RR_PRERUSENI;
if((ododo>odo_cihla)&&(ododo<(odo_cihla+8))) rr=RR_PRERUSENI;
if((ododo>odo_tunel)&&(ododo<(odo_tunel+8))) rr=RR_PRERUSENI;
 
// Elektronicky diferencial 2. cast
if (r1>(CASAVR-CASMIN-rr)) r1=(r1<<1)+rr-(CASAVR-CASMIN); // Neco jako nasobeni
if (r2>(CASAVR-CASMIN-rr)) r2=(r2<<1)+rr-(CASAVR-CASMIN); // rozsah 1 az 92 pro rr=0 // rozsah 1 az 154 pro rr=63
 
//!!! pro zatuhle prevodovky
// r1<<=1; // Rychlost je dvojnasobna
// r2<<=1; // Rozsah 2 az 184 pro rr=0
 
if ((stav==jizda)||(stav==cihla)||(stav==rozjezd)) //||(stav==pocihle)) // Jizda
{
set_pwm1_duty(r1);
set_pwm2_duty(r2);
}
else
{
set_pwm1_duty(0); // Zastaveni
set_pwm2_duty(0);
};
 
if((stav==rozjezd)&&(get_timer1()>10)) // musi ujet alespon 31cm
{
ext_int_edge(H_TO_L); // Nastav podminky preruseni od cihly
INT0IF=0; // Zruseni predesle udalosti od startera
enable_interrupts(INT_EXT);
enable_interrupts(GLOBAL);
stav=jizda;
};
 
if(stav==start) // Snimkuje, toci servem a ceka na start
{
set_adc_channel(MODRA); // Kroutitko na vystredeni predniho kolecka
Delay_ms(1);
stred=read_adc();
if(!input(PROXIMITY))
{
disp(0x80);
while(input(PROXIMITY)); // Cekej, dokud starter neda ruku pryc
set_timer1(0); // Vynuluj citac odometrie
set_pwm1_duty(255); // Rychly rozjezd !!! Zkontrolovat na oscyloskopu
set_pwm2_duty(255);
disp(0x01);
while(get_timer1()<=4) // Ujed alespon 12cm
{
set_adc_channel(LMAX); // Levy UV sensor
delay_us(40);
if(read_adc()<THR) {cas=CASMIN; break;}; // Prejeli jsme caru vlevo
set_adc_channel(RMAX); // Pravy UV sensor
delay_us(40);
if(read_adc()<THR) {cas=CASMAX; break;}; // Prejeli jsme caru vpravo
cas=CASAVR-CASMIN; // Cara je rovne
};
stav=rozjezd;
};
}
 
pom=0x80; // Zobrazeni pozice cary na displayi
for(n=CASMAX/8; n<cas; n+=CASMAX/8) pom>>=1;
disp(pom);
 
while(true) // Ve zbytku casu snimku cti krajni UV senzory a naraznik
{
if(BUMPER) // Sakra, do neceho jsme narazili a nevideli jsme to!
{
bum();
SaveLog(); // Zapis Black Boxu do EEPROM
delay_ms(TUHOS); //!!! Zatuhle prevodovky
set_pwm1_duty(200); // pomalu vpred
set_pwm2_duty(200);
output_low(MOT_L);
output_low(MOT_R);
cas=CASAVR-CASMIN;
};
set_adc_channel(LMAX); // Levy UV sensor
for(n=0;n<20;n++) if(input(HREF)) goto next_snap;
if(read_adc()<THR) cas=CASMIN;
set_adc_channel(RMAX); // Pravy UV sensor
for(n=0;n<20;n++) if(input(HREF)) goto next_snap;
if(read_adc()<THR) cas=CASMAX;
};
}
}
Property changes:
Added: svn:keywords
+Id Rev
\ No newline at end of property
/roboti/istrobot/camerus/SW/876/objizdka_L.c
0,0 → 1,183
// **** Objeti cihly vlevo **** LLLL
 
#define L_TOUCH 1 // Cara vlevo
#define R_TOUCH 2 // Cata vpravo
#define B_TOUCH 3 // Both
 
int8 n;
int8 r1,r2,rr;
int8 touch;
enum okolo_cihly {pred_carou,na_care,po_care};
okolo_cihly ridic; // V jakem jsme stavu objizdeni cihly
int8 vzdalenost;
int8 visualisation;
 
stav=cihla; // Dalsi prekazku uz nezaznamenavej (je to s velkou pravdepodobnosti cil)
odocounter=get_timer1();
 
cihla:
 
rr=RR_CIHLA; //!!! Rozumna rychlost pro objizdeni cihly (bylo by lepsi rychlost zvysovat) a pri detekci pohybu zase snizit
disp(0x99);
set_pwm1_duty(0); // zabrzdi levym kolem, prave vpred
set_pwm2_duty(255);
output_high(MOT_L);
output_low(MOT_R);
while(true) // Na zacatku se vyhni cihle, zatoc co muzes
{
cas=CASMIN-5; // jeste vic nez hodne do leva
 
if(BUMPER) // Narazili jsme do cihly, musime couvnout!
{
bum();
SaveLog(); // Zapis Black Boxu do EEPROM
delay_ms(TUHOS); //!!! Zatuhle prevodovky
brzda();
goto cihla; // Znovu zacni cihlu objizdet
};
 
set_pwm1_duty(0);
set_pwm2_duty(255); // !!! mozna prilis maly vykon pro rozjezd pro zatuhlou prevodovku
output_high(MOT_L); // leve kolo reverz
output_low(MOT_R); // prave kolo vpred
if(get_timer1()>(odocounter+5)) // konec zatacky?
{
disp(0x66);
break;
}
SetServoQ(cas);
delay_ms(18);
};
 
//------ Objeti cihly v konstantni vzdalenosti ------
touch=0; // Indikator detekce cary pri objizdeni
ridic=pred_carou;
cas=CASAVR-CASMIN; // rovne
output_low(MOT_L); // vpred
output_low(MOT_R);
visualisation=0;
while(true)
{
if(BUMPER) // Narazili jsme do cihly, musime couvnout!
{
bum();
SaveLog(); // Zapis Black Boxu do EEPROM
delay_ms(TUHOS); //!!! Zatuhle prevodovky
set_pwm1_duty(160); // vpred
set_pwm2_duty(160);
output_low(MOT_L);
output_low(MOT_R);
cas=CASMIN;
};
 
delta_bearing=bearing-bearing_offset;
visualisation=(delta_bearing & 0xF0) | (visualisation & 0x0F);
if(IRRX) // hrozi celni srazka s cihlou v prubehu objizdeni
{
cas=CASMIN;
}
else
{
if((vzdalenost!=0)||!input(PROXIMITY)||((delta_bearing>60)&&(delta_bearing<128))) // Udrzovani konstantni vzdalenosti od cihly
{
if(cas>(CASMIN+30)) cas-=30;
}
else
{
if(cas<(CASMAX-30)) cas+=30;
};
};
// Elektronicky diferencial
if(cas<CASAVR) {r1=cas-CASMIN; r2=CASAVR-CASMIN;}; // Normovani vystupni hodnoty radkoveho snimace
if(cas==CASAVR) {r1=cas-CASMIN; r2=cas-CASMIN;}; // pro rizeni rychlosti motoru
if(cas>CASAVR) {r1=CASAVR-CASMIN; r2=CASMAX-cas;}; // Rozsah 1 az 92
 
if (r1>(CASAVR-CASMIN-rr)) r1=(r1<<1)+rr-(CASAVR-CASMIN); // Neco jako nasobeni
if (r2>(CASAVR-CASMIN-rr)) r2=(r2<<1)+rr-(CASAVR-CASMIN);
 
//!!! pro zatuhle prevodovky
// r1<<=1; // Rychlost je dvojnasobna
// r2<<=1; // Rozsah 2 az 184 pro rr=0
 
set_pwm1_duty(r1); // Nastav rychlost motoru
set_pwm2_duty(r2);
 
SetServoQ(cas);
 
i2c_start(); // Sonar Ping
i2c_write(SONAR_ADR);
i2c_write(0x0);
i2c_write(0x52); // mereni v us
i2c_stop();
 
for(n=1;n<=90;n++) // 18ms testovani cary do dalsi korekce serva
{
set_adc_channel(LMAX);
delay_us(100);
if(read_adc()<THR) touch|=L_TOUCH;
set_adc_channel(RMAX);
delay_us(100);
if(read_adc()<THR) touch|=R_TOUCH;
};
 
i2c_start(); // Odraz ze sonaru
i2c_write(SONAR_ADR);
i2c_write(0x3);
i2c_stop();
i2c_start();
i2c_write(SONAR_ADR+1);
vzdalenost=i2c_read(0);
i2c_stop();
 
i2c_start(); // Cteni kompasu
i2c_write(COMPAS_ADR);
i2c_write(0x1); // uhel 0-255
i2c_stop();
i2c_start();
i2c_write(COMPAS_ADR+1);
bearing=i2c_read(0);
i2c_stop();
 
if(touch==L_TOUCH) visualisation|=0x2;
if(touch==R_TOUCH) visualisation|=0x1;
if((touch==B_TOUCH)&&(ridic==pred_carou)) ridic=na_care;
if((ridic==na_care)&&(touch==0)) break;
if(ridic==na_care) touch=0;
disp(visualisation);
};
disp(0xC3);
 
set_pwm1_duty(0); //!!! pred zatuhlejma prevodovkama tam bylo 20 a 200
set_pwm2_duty(255);
output_high(MOT_L);
output_low(MOT_R);
delay_us(40);
odocounter=get_timer1(); // Poznamenej aktualni stav odometrie
while (true) // Znovu se musime dotknout cary
{
for(n=1;n<=90;n++) // 18ms testovani cary do dalsi korekce serva
{
set_adc_channel(LMAX); // Levy UV sensor
delay_us(100);
if(read_adc()<THR) // Dotkli jsme se levym senzorem
{
disp(0xE0);
cas=CASAVR-CASMIN; // nastavime, ze cara je rovne
goto cara;
};
set_adc_channel(RMAX); // Pravy UV sensor
delay_us(100);
if((get_timer1()>=(odocounter+2)) && (read_adc()<THR)) // Pravym senzorem nesmime caru prejet!
{
disp(0x07);
cas=CASMAX; // kdyz prejedem, tak nastavime, ze cara je vpravo
goto cara;
};
}
SetServoQ(CASMIN-5); // max. max. doleva L
}
 
cara:
 
output_low(MOT_L); // oba motory vpred
output_low(MOT_R);
/roboti/istrobot/camerus/SW/876/diag.c
0,0 → 1,68
//--- Diagnostika cidel a vymazani EEPROM ---
void diag()
{
int8 n;
 
// Vymaz Black Box v EEPROM
for(n=0;n<255;n++) write_eeprom(n,0);
bb_l[0]=0; // Zapis na pozici 0 vzdalenost 0
bb_h[0]=0;
bb_f[0]=0;
write_eeprom(EEMAX,0); // Zapis do EEPROM pocet zaznamu 0, tedy jeden zaznam
for(n=0;n<=4;n++)
{
disp(0x55); // Blikni pro potvrzeni
delay_ms(200);
disp(0xAA);
delay_ms(200);
};
 
while(true)
{
if(!IRRX)
{
int8 ble;
 
i2c_start(); // Cteni kompasu
i2c_write(COMPAS_ADR);
i2c_write(0x1);
i2c_stop();
i2c_start();
i2c_write(COMPAS_ADR+1);
ble=i2c_read(0);
i2c_stop();
disp(ble);
delay_ms(200);
}
else
{
i2c_start(); // Diagnostika sonaru
i2c_write(SONAR_ADR);
i2c_write(0x02); // dosah
i2c_write(0x03); // n*43mm
i2c_stop();
i2c_start();
i2c_write(SONAR_ADR);
i2c_write(0x01); // zesileni
i2c_write(0x01); // male, pro eliminaci echa z minuleho mereni
i2c_stop();
 
i2c_start(); // Sonar Ping
i2c_write(0xE0);
i2c_write(0x0);
i2c_write(0x51); // 50 mereni v palcich, 51 mereni v cm, 52 v us
i2c_stop();
delay_ms(100);
i2c_start(); // Odraz ze sonaru
i2c_write(0xE0);
i2c_write(0x3);
i2c_stop();
i2c_start();
i2c_write(0xE1);
n=i2c_read(0);
i2c_stop();
disp(n); // Zobrazeni hodnoty ze sonaru a zaroven diagnostika predniho IR cidla
delay_ms(200);
}
}
}
/roboti/istrobot/camerus/SW/876/camerus.PJT
0,0 → 1,57
[PROJECT]
Target=camerus.HEX
Development_Mode=
Processor=0x876A
ToolSuite=CCS
 
[Directories]
Include=C:\Program Files\PICC\devices\;C:\Program Files\PICC\Dr
Library=
LinkerScript=
 
[Target Data]
FileList=C:\dokumenty\svn\Kaklik\roboti\istrobot\camerus\SW\876\camerus.c
BuildTool=C-COMPILER
OptionString=+FM
AdditionalOptionString=
BuildRequired=1
 
[camerus.c]
Type=4
Path=
FileList=
BuildTool=
OptionString=
AdditionalOptionString=
 
[mru-list]
1=camerus.c
 
[Windows]
0=0000 camerus.c 0 0 796 451 3 0
 
[Opened Files]
1=C:\dokumenty\svn\Kaklik\roboti\istrobot\camerus\SW\876\camerus.c
2=C:\dokumenty\svn\Kaklik\roboti\istrobot\camerus\SW\876\camerus.h
3=C:\Program Files\PICC\devices\16F876A.h
4=C:\dokumenty\svn\Kaklik\roboti\istrobot\camerus\SW\876\objizdka_L.c
5=C:\dokumenty\svn\Kaklik\roboti\istrobot\camerus\SW\876\diag.c
6=
[debugperif]
selected=Analog/Digital Conv
[debugram]
autoread=1
[debugeedata]
autoread=1
[debugbreak]
count=0
[pcwdebug]
watchcol0=75
[debugwatch]
count=0
[debugexpr]
expr=
sideeffects=0
[Units]
Count=1
1=C:\dokumenty\svn\Kaklik\roboti\istrobot\camerus\SW\876\camerus.c (main)
/roboti/istrobot/camerus/SW/876/camerus.h
0,0 → 1,16
#include <16F876A.h>
#device adc=8
 
#FUSES NOWDT //No Watch Dog Timer
#FUSES HS //High speed Osc (> 4mhz)
#FUSES NOPUT //No Power Up Timer
#FUSES NOPROTECT //Code not protected from reading
#FUSES NODEBUG //No Debug mode for ICD
#FUSES NOBROWNOUT //No brownout reset
#FUSES NOLVP //No low voltage prgming, B3(PIC16) or B5(PIC18) used for I/O
#FUSES NOCPD //No EE protection
#FUSES NOWRT //Program memory not write protected
 
#use delay(clock=20000000)
#use i2c(Master,Fast,sda=PIN_C4,scl=PIN_C3,force_hw)
 
/roboti/istrobot/camerus/SW/876
Property changes:
Added: svn:ignore
+*.bak
+*.BAK
+*.cof
+*.err
+*.hex
+*.lst
+*.sta
+*.sym
+*.tre
/roboti/istrobot/camerus/SW/873/camerus.PJT
0,0 → 1,55
[PROJECT]
Target=camerus.HEX
Development_Mode=
Processor=0x873A
ToolSuite=CCS
 
[Directories]
Include=C:\Program Files\PICC\devices\;C:\Program Files\PICC\Dr
Library=
LinkerScript=
 
[Target Data]
FileList=C:\dokumenty\svn\Kaklik\roboti\istrobot\camerus\SW\873\camerus.c
BuildTool=C-COMPILER
OptionString=+FM
AdditionalOptionString=
BuildRequired=1
 
[camerus.c]
Type=4
Path=
FileList=
BuildTool=
OptionString=
AdditionalOptionString=
 
[mru-list]
1=camerus.c
 
[Windows]
0=0000 camerus.c 0 0 796 451 3 0
 
[Opened Files]
1=C:\dokumenty\svn\Kaklik\roboti\istrobot\camerus\SW\873\camerus.c
2=C:\dokumenty\svn\Kaklik\roboti\istrobot\camerus\SW\873\camerus.h
3=C:\Program Files\PICC\devices\16F873A.h
4=
[debugperif]
selected=Analog/Digital Conv
[debugram]
autoread=1
[debugeedata]
autoread=1
[debugbreak]
count=0
[pcwdebug]
watchcol0=75
[debugwatch]
count=0
[debugexpr]
expr=
sideeffects=0
[Units]
Count=1
1=C:\dokumenty\svn\Kaklik\roboti\istrobot\camerus\SW\873\camerus.c (main)
/roboti/istrobot/camerus/SW/873/camerus.c
0,0 → 1,512
//********* Robot Camerus pro IstRobot 2007 ************
//"$Id: camerus.c 229 2007-04-09 11:41:19Z kakl $"
//*****************************************************
 
#include ".\camerus.h"
 
#USE FAST_IO (C) // Brana C je ve FAST_IO modu, aby slo rychle cist z kamery
 
// A/D vstupy
#define RMAX 4 // AN4/RA5 - leve cidlo na vyjeti z cary
#define LMAX 3 // AN3/RA3 - prave cidlo na vyjeti z cary
#define CERVENA 2 // AN2/RA2 - cervene kroutitko
#define ZELENA 1 // AN1/RA0 - zelene kroutitko
#define MODRA 0 // AN0/RA1 - modre kroutitko
 
// I/O
#define HREF PIN_C5 // Signal HREF z kamery (v H po celou dobu radku)
#define PIX PIN_C6 // Vstup pro body z kamery (za trivstupim hradlem OR (dig. komparator))
#define SERVO PIN_B4 // Vystup na servo (1 az 2ms po cca 20ms (synchronizovano snimkovym kmitoctem))
#define MOT_L PIN_B5 // Smer otaceni leveho motoru; druhy pol je RC2
#define MOT_R PIN_B6 // Smer otaceni praveho motoru; druhy pol je RC1
#define MOT_1 PIN_C1 // PWM vystpy motoru
#define MOT_2 PIN_C2 //
#define DATA PIN_B2 // K modulu LEDbar data
#define CP PIN_B1 // K modulu LEDbar hodiny
//#define ODO PIN_C0 // Ze snimace z odometrie z praveho kola na TIMER1
// Jeden impuls je 31,25mm
#define IRRX PIN_B0 // Vstup INT, generuje preruseni pri prekazce
#define IRTX PIN_B3 // Modulovani vysilaci IR LED na detekci prekazky
#define PROXIMITY PIN_C7 // Cidlo kratkeho dosahu na cihlu
 
#define CASMIN 6 // Rozsah radku snimace
#define CASMAX 192
#define CASAVR ((CASMAX+CASMIN) / 2)
 
#define OFFSETO 0x9F //0x9F // Vystredeni serva pro objeti prekazky
 
#define THR 90 // Threshold pro UV cidla na caru
 
#byte INTCON = 0x0B // Interrupt configuration register
#bit GIE = INTCON.7
#bit PEIE = INTCON.6
#bit TMR0IE = INTCON.5
#bit INT0IE = INTCON.4
#bit RBIE = INTCON.3
#bit TMR0IF = INTCON.2
#bit INT0IF = INTCON.1
#bit RBIF = INTCON.0
 
enum stavy {start,rozjezd,jizda,cihla,pocihle,cil};
stavy stav; // Kde jsme na trati
int8 cas; // Cas hrany bila/cerna v radce
int8 stred; // Vystredeni kolecka
int16 odocounter; // Zaznamenani aktualniho stavu pocitadla odometrie
int8 rr; // Promenna na ulozeni Rozumne rychlost
int8 rrold;
//int8 pole_h[0x40];
int8 pole_l[0x40];
 
// Zobrazeni jednoho byte na modulu LEDbar
inline void disp(int8 x)
{
int n;
 
for(n=0;n<=7;n++)
{
if (x & 1 == 1) output_low(DATA); else output_high(DATA);
output_high(CP);
x>>=1;
output_low(CP);
}
}
 
// Blikani LEDbarem ve stilu Night Rider
void NightRider(int8 x)
{
int n,i,j;
 
for(j=0;j<x;j++)
{
i=0x01;
for(n=0;n<7;n++)
{
disp(i);
rotate_left(&i, 1);
delay_ms(40);
}
for(n=0;n<7;n++)
{
disp(i);
rotate_right(&i, 1);
delay_ms(40);
}
}
disp(i);
delay_ms(40);
i=0;
disp(i);
}
 
// Brzdeni motorama stridou 1:1
void brzda()
{
int8 n,i;
 
set_pwm1_duty(0); // vypni PWM
set_pwm2_duty(0);
setup_ccp1(CCP_OFF);
setup_ccp2(CCP_OFF);
for (n=0;n<200;n++)
{
output_low(MOT_L);
output_low(MOT_R);
output_high(MOT_1);
output_high(MOT_2);
delay_us(200);
output_high(MOT_L);
output_high(MOT_R);
output_low(MOT_1);
output_low(MOT_2);
delay_us(200);
}
output_low(MOT_L); // smer vpred
output_low(MOT_R);
setup_ccp1(CCP_PWM); // RC1 // Zapni PWM pro motory
setup_ccp2(CCP_PWM); // RC2
}
 
void SetServo(int8 angle)
{
int8 n;
 
for(n=0; n<14; n++)
{
output_high(SERVO); // Odvysilani impuzu 1 az 2ms pro servo
delay_us(1000);
delay_us(stred);
delay_us(stred);
delay_us(stred);
delay_us(angle);
delay_us(angle);
output_low(SERVO);
delay_ms(18);
}
}
 
inline void SetServoQ(int8 angle)
{
output_high(SERVO); // Odvysilani impuzu 1 az 2ms pro servo
delay_us(1000);
delay_us(stred);
delay_us(stred);
delay_us(stred);
delay_us(angle);
delay_us(angle);
output_low(SERVO);
}
 
//---------------------------- INT --------------------------------
#int_EXT
EXT_isr() // Preruseni od prekazky
{
set_pwm1_duty(0); // zabrzdi levym kolem, prave vypni
set_pwm2_duty(0);
output_high(MOT_L);
output_low(MOT_R);
// Ujistime se, ze prijaty signal je z naseho IR vysilace
output_high(IRTX); // Vypni LED na detekci prekazky
delay_ms(2);
if (!input(IRRX)) // stale nas signal?
{
output_low(MOT_L); // je odraz -> vpred
output_low(MOT_R);
return;
};
output_low(IRTX); // Zapni LED na detekci prekazky
delay_ms(10);
if (input(IRRX)) // stale nas signal?
{
output_low(MOT_L); // neni odraz -> vpred
output_low(MOT_R);
return;
};
 
//!!! if(stav==cihla) while(true); // Zastav na furt, konec drahy
// if(stav==cihla) return; // Po druhe nic neobjizdej
// Pozor na rozjezd
 
if(stav==jizda) // Objed cihlu
{
#include ".\objizdka_L.c"
}
}
 
 
//---------------------------------- MAIN --------------------------------------
void main()
{
int8 offset; // Promena pro ulozeni offsetu
int8 r1; // Rychlost motoru 1
int8 r2; // Rychlost motoru 2
 
setup_adc_ports(ALL_ANALOG); // Zapnuti A/D prevodniku pro cteni kroutitek
setup_adc(ADC_CLOCK_INTERNAL);
setup_timer_0(RTCC_INTERNAL|RTCC_DIV_1); // Casovac pro mereni casu hrany W/B v radce
setup_timer_1(T1_EXTERNAL); // Cita pulzy z odometrie z praveho kola
setup_timer_2(T2_DIV_BY_16,255,1); // Casovac PWM motoru
setup_ccp1(CCP_PWM); // RC1 // PWM pro motory
setup_ccp2(CCP_PWM); // RC2
setup_comparator(NC_NC_NC_NC);
setup_vref(FALSE);
 
set_tris_c(0b11111001); // Nastaveni vstup/vystup pro branu C, protoze se nedela automaticky
 
set_pwm1_duty(0); // Zastav motory
set_pwm2_duty(0);
output_low(MOT_L); // Nastav smer vpred
output_low(MOT_R);
 
output_low(IRTX); // Zapni LED na detekci prekazky
 
NightRider(1); // Aby se poznalo, ze byl RESET
// taky se musi pockat, nez se rozjede kamera, nez se do ni zacnou posilat prikazy
 
 
/*
for(cas=0;cas<=0x3F;cas++)
{
pole_h[cas]=0x80|cas;
pole_l[cas]=cas;
}
for(cas=0;cas<=0x7F;cas+=2)
{
write_eeprom(cas,pole_h[cas/2]);
write_eeprom(cas+1,pole_l[cas/2]);
}
*/
 
while(true)
{
output_high(PIN_B0);
delay_ms(200);
output_low(PIN_B0);
delay_ms(200);
}
 
//... Nastaveni sonaru ...
i2c_start();
i2c_write(0xE0);
i2c_write(0x02); // dosah
i2c_write(0x03); // n*43mm
i2c_stop();
i2c_start();
i2c_write(0xE0);
i2c_write(0x01); // zesileni
i2c_write(0x01); // male, pro eliminaci echa z minuleho mereni
i2c_stop();
 
// pro ladeni sonaru
/*
while(true)
{
i2c_start(); // Sonar Ping
i2c_write(0xE0);
i2c_write(0x0);
i2c_write(0x51); // 50 mereni v palcich, 51 mereni v cm, 52 v us
i2c_stop();
delay_ms(100);
i2c_start(); // Odraz ze sonaru
i2c_write(0xE0);
i2c_write(0x3);
i2c_stop();
i2c_start();
i2c_write(0xE1);
cas=i2c_read(0);
i2c_stop();
disp(cas);
}
*/
 
//... Nastaveni kamery ...
i2c_start(); // Soft RESET kamery
i2c_write(0xC0); // Pro single slave musi mit vsechny zapisy adresu C0h
i2c_write(0x12); // Adresa registru COMH
i2c_write(0x80 | 0x24); // Zapis ridiciho slova
i2c_stop();
 
i2c_start(); // BW
i2c_write(0xC0);
i2c_write(0x28);
i2c_write(0b01000001);
i2c_stop();
 
/*
i2c_start(); // Contrast (nema podstatny vliv na obraz)
i2c_write(0xC0);
i2c_write(0x05);
i2c_write(0xA0); // 48h
i2c_stop();
 
i2c_start(); // Band Filter (pokud by byl problem se zarivkama 50Hz)
i2c_write(0xC0);
i2c_write(0x2D);
i2c_write(0x04 | 0x03);
i2c_stop();
*/
 
i2c_start(); // Fame Rate
i2c_write(0xC0);
i2c_write(0x2B);
i2c_write(0x00); // cca 17ms (puvodni hodnota 5Eh = 20ms)
i2c_stop();
 
i2c_start(); // VSTRT
i2c_write(0xC0);
i2c_write(0x19);
i2c_write(118); // prostredni radka
i2c_stop();
 
i2c_start(); // VEND
i2c_write(0xC0);
i2c_write(0x1A);
i2c_write(118);
i2c_stop();
 
NightRider(1); // Musi se dat cas kamere na AGC a AEC
 
{ // Mereni expozice
int8 t1,t2;
 
i2c_start(); // Brightness, zacni od uplne tmy
i2c_write(0xC0);
i2c_write(0x06);
i2c_write(0); // 80h default
i2c_stop();
delay_ms(50);
 
for(offset=0x04;offset<(255-0x04);offset+=0x04) // Zacni od jasu 10h
{
i2c_start(); // Brightness
i2c_write(0xC0);
i2c_write(0x06);
i2c_write(offset); // 80h default
i2c_stop();
disp(offset);
delay_ms(50);
 
t1=0;
t2=0;
while(!input(HREF)); // Cekej nez se zacnou posilat pixely z radky
delay_ms(5);
while(!input(HREF)); // Cekej nez se zacnou posilat pixely z radky
set_timer0(0); // Vynuluj pocitadlo casu
if(!input(PIX)) continue;
while(input(PIX));
t1=get_timer0(); // Precti cas z citace casu hrany
set_timer0(0); // Vynuluj pocitadlo casu
while(!input(PIX));
t2=get_timer0();
 
if((t1>60) && (t1<140) && (t2>5) && (t2<=10)) break; // Vidis, co mas?
 
delay_ms(2); // Preskoc druhou radku z kamery
};
delay_ms(1000); // Nech chvili na displayi zmerenou hodnotu
}
 
set_adc_channel(CERVENA); // --- Kroutitko pro jas ---
delay_ms(1);
offset=read_adc();
offset &= 0b11111100; // Dva nejnizsi bity ignoruj
// offset += 0x70; // Jas nebude nikdy nizsi
disp(offset);
i2c_start(); // Brightness
i2c_write(0xC0);
i2c_write(0x06);
i2c_write(offset); // 80h default
i2c_stop();
delay_ms(1000); // Nech hodnotu chvili na displayi
 
set_adc_channel(ZELENA); // --- Kroutitko pro vykon motoru ---
delay_ms(1);
rr=read_adc()>>2; // 0-31 // Pokud by se zvetsil rozsah, tak zkontrolovat jakonasobeni !!!
rrold=rr;
 
cas=CASAVR-CASMIN; // Inicializace promenych, aby neslo servo za roh
// a aby se to rozjelo jeste dneska
stav=start; // Jsme na startu
set_timer1(0); // Vynuluj citac odometrie
 
// ........................... Hlavni smycka ................................
while(true)
{
int8 pom;
int8 n;
 
next_snap:
 
pom=0;
disable_interrupts(GLOBAL); //----------------------- Critical
while(input(HREF)); // Preskoc 1. radku
while(!input(HREF)); // Cekej nez se zacnou posilat pixely z 2. radky
set_timer0(0); // Vynuluj pocitadlo casu
while(input(HREF)) // Po dobu vysilani radky cekej na hranu W/B
{
// !!!!Dodelat rozpoznani cerne cary napric pro zastaveni ?
if(!input(PIX)) // Pokud se X-krat za sebou precetla CERNA
if(!input(PIX))
// if(!input(PIX))
{
pom=get_timer0(); // Precti cas z citace casu hrany
break;
};
};
while(input(HREF)); // Pockej na shozeni signalu HREF
 
if((pom<CASMAX) && (pom>CASMIN)) cas=pom; // Orizni konce radku
// Na konci obrazovaho radku to blbne. Jednak chyba od apertury
// a vubec to nejak na kraji nefunguje.
 
output_high(SERVO); // Odvysilani impuzu 1 az 2ms pro servo
delay_us(1000);
delay_us(stred);
delay_us(stred);
delay_us(stred);
delay_us(cas);
delay_us(cas);
output_low(SERVO);
 
// Elektronicky diferencial
if(cas<CASAVR) {r1=cas-CASMIN; r2=CASAVR-CASMIN;}; // Normovani vystupni hodnoty radkoveho snimace
if(cas==CASAVR) {r1=cas-CASMIN; r2=cas-CASMIN;}; // pro rizeni rychlosti motoru
if(cas>CASAVR) {r1=CASAVR-CASMIN; r2=CASMAX-cas;}; // Rozsah 1 az 92
 
enable_interrupts(GLOBAL); //----------------------- Critical
 
if (r1>(CASAVR-CASMIN-rr)) r1=(r1<<1)+rr-(CASAVR-CASMIN); // Neco jako nasobeni
if (r2>(CASAVR-CASMIN-rr)) r2=(r2<<1)+rr-(CASAVR-CASMIN);
 
// r1<<=1; // Rychlost je dvojnasobna
// r2<<=1; // Rozsah 2 az 184
 
/* Nerozumna rychlost po cihle
if ((stav==cihla)&&(get_timer1()>(odocounter+5))) // Snizime rychlost po ujeti
{
rr=rrold;
stav=pocihle;
};
*/
if ((stav==jizda)||(stav==cihla)||(stav==rozjezd)) //||(stav==pocihle)) // Jizda
{
set_pwm1_duty(r1);
set_pwm2_duty(r2);
}
else
{
set_pwm1_duty(0); // Zastaveni
set_pwm2_duty(0);
};
 
if((stav==rozjezd)&&(get_timer1()>10)) // musi ujet alespon 31cm
{
ext_int_edge(H_TO_L); // Nastav podminky preruseni od cihly
INT0IF=0; // Zruseni predesle udalosti od startera
enable_interrupts(INT_EXT);
enable_interrupts(GLOBAL);
stav=jizda;
};
 
if(stav==start) // Snimkuje, toci servem a ceka na start
{
set_adc_channel(MODRA); // Kroutitko na vystredeni predniho kolecka
Delay_ms(1);
stred=read_adc();
if(!input(PROXIMITY))
{
disp(0x80);
while(input(PROXIMITY)); // Cekej, dokud starter neda ruku pryc
set_timer1(0); // Vynuluj citac odometrie
set_pwm1_duty(255); // Rychly rozjezd !!! Zkontrolovat na oscyloskopu
set_pwm2_duty(255);
disp(0x01);
while(get_timer1()<=4) // Ujed alespon 12cm
{
set_adc_channel(LMAX); // Levy UV sensor
delay_us(40);
if(read_adc()<THR) {cas=CASMIN; break;}; // Prejeli jsme caru vlevo
set_adc_channel(RMAX); // Pravy UV sensor
delay_us(40);
if(read_adc()<THR) {cas=CASMAX; break;}; // Prejeli jsme caru vpravo
cas=CASAVR-CASMIN; // Cara je rovne
};
stav=rozjezd;
};
}
 
pom=0x80; // Zobrazeni pozice cary na displayi
for(n=CASMAX/8; n<cas; n+=CASMAX/8) pom>>=1;
disp(pom);
 
while(true) // Ve zbytku casu snimku cti krajni UV senzory
{
set_adc_channel(LMAX); // Levy UV sensor
for(n=0;n<20;n++) if(input(HREF)) goto next_snap;
if(read_adc()<THR) cas=CASMIN;
set_adc_channel(RMAX); // Pravy UV sensor
for(n=0;n<20;n++) if(input(HREF)) goto next_snap;
if(read_adc()<THR) cas=CASMAX;
};
}
}
/roboti/istrobot/camerus/SW/873/camerus.h
0,0 → 1,16
#include <16F873A.h>
#device adc=8
 
#FUSES NOWDT //No Watch Dog Timer
#FUSES HS //High speed Osc (> 4mhz)
#FUSES NOPUT //No Power Up Timer
#FUSES NOPROTECT //Code not protected from reading
#FUSES NODEBUG //No Debug mode for ICD
#FUSES NOBROWNOUT //No brownout reset
#FUSES NOLVP //No low voltage prgming, B3(PIC16) or B5(PIC18) used for I/O
#FUSES NOCPD //No EE protection
#FUSES NOWRT //Program memory not write protected
 
#use delay(clock=20000000)
#use i2c(Master,Fast,sda=PIN_C4,scl=PIN_C3,force_hw)
 
/roboti/istrobot/camerus/SW/873
Property changes:
Added: svn:ignore
+*.bak
+*.BAK
+*.cof
+*.err
+*.hex
+*.lst
+*.sta
+*.sym
+*.tre
/roboti/istrobot/camerus/HW/CAM_AMA/BOARD.pdf
0,0 → 1,159
%PDF-1.3
%Ç쏢
5 0 obj
<</Length 6 0 R/Filter /FlateDecode>>
stream
+óIššrÐJÒ˹Zj»ç—³°è$g–H›KƒjÒPC>g¥DÝÖM*¦m¸vaŒ¸ÎAwj2QéЈŠÓ`Ë'Ã%K­cöNò“iXÎÊÄêâ­[JÍ"M4CC¤vsaÙ
+­(Ÿ~¯±Ú±¯­hÿ\Èã&õ*ÃïêW)†½¢¢cºJÓU[Þ9]¥\Û«¾"㦹ÛtUGãÅ骎MϜ`
+Z·ÞHòþœpßÆ
+ SMʘj
+Z&½³¢ºî†NS@“t§[æ°é%ͽ2Ê$±YNÑKÂTSpšnt>Ïwb1ס'7égQ¯æÁ)
+Z&íòlwýp»ÉGÞ1]5øŸØïöjziÁÍÆIWâ y­lüô èkƒÔ6ønoÔF¥»†mM'CûVÕ7
+Ö'ñ½…Û%‰>ºÎAö^«®²äáÄN9yo1úÜᵅÓ
+óhLÍ9h™TÞ@ôdØþ³™oåá)]IŠ3~ªÆ`ydhå¥üL%‡8Í¢o‚tIÞÍ,X™  {³ôf2³Pz`ðkf1'÷×S‚ƒÌ,xÁ6:›úfyJW’šYƒå™f̓s͂=®Z[&ΒÑsÁ؆Œ¹M©-<UµEyú8õ çV“Jº¨-$>)¼´ššsÐ2)¾d¾
+O]½¾†çá)]I*¥¼ëɎ›Ö/åg*qP2‹Ö–Y·ø¼©zU£¶ð㥇Y´¶8™Y(c ¶Ž0‹}Þ™YP[è¶{š´¶8­$5³ Ë3Í,šç ®9îðDm©ðáóS¾ŸpíÖ^¨%N•¾ÁDzštTÓ5¼¶Tx9hjÎAˤ§¬Z[˜kKpÐJRÑ{jmÑrÞ³sµÔ8(™EûF˜ÂOÁ»™Ežº.ö0 kKp™…ÒQM×ðÚÂBkjÎAf©-4K?Íý ³<¥+IÍ,ˆÁrN3‹-"ñ%â ¢l[ê==Ñi=Ï
+eÛ¢Ì3HŒƒpfŠµ8e·žˆ¤½€ñ•8h™½ÇØõlW¤ §¿:-—²É=­'byD——ò3•8(™ÅF†[ôDäÝ̂¶…Åô0‹¶-ÎAfJwë‰HG˜Åú=ã 3 {.áš„<éri˜m Ë3Í,šç ݔ‰9“›2ñmI¯cò][
+<B¤Ž¨3j‹1Vúœƒ°rš§šÝµE‰>Îð±ÔŒƒ–IOñ³.‡zëYÂÃóð”®$½}·ÜÙº¿¢”Ÿ©ÄAÉ,¬- ²Ý¥àÝÌ"uD÷Žö0 kKp™…R| ïfÛẑšq™EÚš¥Ÿf€~†YžÒ•¤fÆ@y¦™Åò`Ä&'$`vM&U_ÿþ?(=&ûϤç™>÷°ï@Ïç9‰Ÿ¡Ò'ᬜ}™2O'5’Óv†KqbܘFzè«“ÎAˤS4`]ç‚"…óˆ<<¤+Iq¨­o²<Ðe¥üL%â‚UÛÜ,\$±Å¢MÍÒë©fárÍbÌE 㠙°:\:Ô,J\°âacLÍ9h™tŠ†CÍ¢)À,ÁA+IEï©fÑòˆ./åg*qmœ·d
+–¢Lì>M³(Ÿ1Ӎ™l#L隱pú t‘t¦ÛøJ´\
+f¦@³8-—r· òŽùm–í|E)?S‰ƒôCúõºX©¶Áé˜%-VZe²XzJ„Ž•ÞÆÖãLƒy¦|ùÍ ×þ#ô›g:§ÊÍí[Þª®]hˆÆú–ŽÇÂodúeÞxúV”!ôVhbçñŒ ±X9„Ö±XšÎˆœ­d'^¢•”Ó1U/çgÜóoç+qÐÒó#(ŁÓh×s ¯ÄAˤ²˜;§p.)OŠ+ž‡§t%é¥g ËVê+Jù™JgÙ¹£÷ûpôþp't¸ÙÿOrNÿHîòï?r—ÿù/96¤cC%M©¦øúÛ+Ƀ4¾ðþŽøHG¼ÿ訂/÷æÇvý»íá ÞqXoÔç^xï?ò“2à>þÒýú®_yû%ÏÀä-8_º™ê#yC¾¿zCâã­ª'¸zCú×`ñ/Góu¬¯ðdüüO=›òIyÄ0Rïwõ7¶˜Õ©ØsÖÍlv<Å_ó-ýí/ëË<XuC·y¸ZilÓÞýör?X㠕¼fDsñM|É÷ýGþ¸ØúÕý—îá{ýÊï7ûëv»ð&Îoù–Þò¿â“üó_ÿv„¬“¾ï[Ä·_Å7ë𼮪Å|Éßÿ¿ñßx…ÿÞçûw)'Ÿöú$õè¯Z£›mm6¯úªšéÏ~×cÿ#!ðþÎøHg¼ÿè,ƒ;©¡s–äð[}¿:Ïáq"Ήðg`'Jä3'ò9é¬
+>Ò ï?:cáãëqí¥P<\u¾"œñKwH”2ðbV–Î‰Eœµ—77Äö
+1Gç"ŽÎZÌ¥™.úÆAx7ç¦_XócJ̹Z–ÈÌ%Û²‹æ¤ië!¿lýeWE*÷—¹¤·W8§þçô£™t×ö+ËÝõüwŽåÃ¥ã/ä|¤œ+­ß:áú49óÅjs_ׯÜþý»ã燈>ÿ¼ÄA׏ÇñÓޚoGð€ƒãISsJWÙšÿÆ1 éà‡÷?pðÇJAKþõ(~÷Ët¸Esê${W¿Žñ‘áxÿÑ!~¼.›ñc=®_ûáß??,.»Íjƒ4Bws'}ð®õÂh{åLìX“óqÀɇŒ2Cóß80å#áòþŽpùHGɼÿè(8@ïþ þö‘6?×ÇãÒ!::Jýف<?;°ç§c…n}Ðz4Ñ_<xèWÇ
+I™äõ“é£wºÜìú‘¯?‹+Ñì¢4|»Övð
+µwºdíúŅkËÙº_ØÖíbµv\§¾îÎ9-—ÚµoÏKæ>qõÜǏ¸´s“»_U—/³›~ÁÝôKéô:¼þ
+wîîKQõ@|·Ÿ˜×ƒœÌ(ñóù§£-vˆáûI÷6oί¼™ÞG›1øuÊZ²ˆa„ƒÓ,b1‘G9|XÞ8c ÌCkŒƒ–Ieƀeî§ë+YçȔkè“Y[Ra#¼:7€u_™kzëáÂ2Ç$sZ< õNIIæ´ð¥bsZXsÖ9­Éù-Ì$9-½P]¥xw7'-Ãd®—¬ïdÑÇ=ðCâcŽj3ªxŽÎAœ­Û“>î>¼säëf”êl/MbþÌ#筗™ë¥*Ê÷ÓùF»ý3Ÿ{ü’s·ÎAË¥’é,9á12¨×“{@ª¤åb\Ýn©I*8ИÒnéّ!Z3ô-DÍБ¥ŒåyºŽ™gˆqvïàî.XÍÝ]*—·úd¾[ ³8ÎA뻾’ôΐ-“îÐR9ÐT}œ»wb»thli—°³f×sA+ùAºÁþ£vÿ%6å/ çòïƧ`d֛ÚÚ1¾Úà·)öqã|Ó¿¦™ré#íöËà ÎKìQƲGU.ñåœT 0w=¯Ç/1•ÊT°×¤Û×=×tî>ù4)V—ó?ӌ>ÒåAëRqEF:Ԃõ
+͟ÊeßH†Ù–>|ìsnðn<xÄ?ݑ¥x؛×CҌ+øИ\©±+Zòý ¤‡Ùèw)Ÿ\E¼œeljÑr)ö™l\›lzŒÝÁü”¯R®RÏi+œ\±å
+gȹ¶+š°oÏ9(y®š'ð|é>@÷émêㆵK;²þ«êíªûã.çݽYéíK¦×–qPÜ%
+Ö3iÀ§{잮K}‡ëWéJÒÈ%bìÔk¤©)­$uBæRIFÍ0™Mÿür¸¿ø$¹]‘̓íºlu÷EºÇl(¨ó•8ȝ{)=L—¹ù~»(S9h¹´ù•™Ý݇{äá!]IN<£UÓe¥üL%¢)¹Î…¯ÜœÑ/~ÅéŽÐ¿e•§yÓ÷Vï@=ƒM^ô¬Ã‰'Ä­$½œáë[8Bø™×o¾µuO÷ºþË¥-ÅÈ7îç}±‡k8"—ÆWâ åÒÃ¥óöáå£ú‡¿13m´\*ÉàùöËõjÜí«t%i\®kNxz¹®n*Ëu÷$]Iê®ÞtiÖ¥aK¡¦<蕻Û×(ÅiR+}”R͒ý£ãž`ñ „ŸëdºMø‹'sºŸøÃ¿)wêiW%±Ê‹î;:œôNi堕¤—3¼uۓÔoW9Rë¯ïÞ¼í7Xÿü–ìæ^¶”nV¿•˜_ã+qÐréáÒù
+Kñ1¨Ûnv$¶£ùw_PÍWŒ›s¯9Ç¥å_œ_醻ks¢®©èæÒ5ï_ÝTã:ù},„ÜýÍ¡C¬Ñré®oaU·×áµö)]IŽ±ö¾P©û›ÃtV’^ÎíeºŠ§VRŠ¿9ÏöæPj¥R~ÆÉ`î{¤sð‚õ³-éÁ<üP·’ÌÃÏ3Qö`Ô ³p—WyÙÙ¹ÎAËýRE:uåɈ{¿Œ¯ÄAË¥Ø3¶ñ+ÙR@Óç´’ôòºßKuõȃqÐJÒ˹'Õ(å'O
+Ôš§|3åW÷иëòÃïåEܒʻ<¹}UYåU¤=œô¾P堕¤—3\6ǓÔysXóNß]:y'²ñÏn@mL¹¹´zj5å·¦œUÏ{My¯^Îêeo©yª˜ÿ5ÏÎé]TpÐr).~íìÍST¯€Ý¿JW’Æ%²æ¦º¼ã
+ZIz9w÷V­žZMyЋ©÷¯1 ­»´¹.ïÀa–ìð÷áJMÃÄ1kgº5÷‹kjº‡÷Ãï:¦Cæ8¼ÃTNeÞè¹À‡“ÞelÓJÒËî¢óIê8:½ót‡Òïî¤í7'ÿüvæænž*ížZOùí)gÝóÞSÞ»—³{Ù÷ÜyªßhödfìîmtºÚÚ¼Ku3]–ýÅû’û/´6ßHÌ*¥ëÅ¿úIÆ5æú.¸¥wQÁAË¥»¾9¸¡¦[œƒV’†gæpÿÉÝ©û›£éΔîL9ÓÏtO­¤<sž1ìÍQis]ށûIÆîZӃáò[SGϑÌÃÒx‰TrtôCxÉ– ÍñoÄ¿¹ÆaÑÝÝùðÆ3·»ßµ¿º°øC/ã[oÐûê°·ó=ÒòÝ~–7wU‹EJåþ²ßVwZÓN»5jÁAáÖVÝ%­;å[
+|K¾láÁÖ^׏ï>nÚªKuö¨ëŒúÀkË»Ÿ!÷FŠ;Rܑb,—žÚôÜ̔ß,]ÉNh˳›9¹éWÅ7W´6‡M, wÃﹸòtŸºC奮EáĄïubÂç–ËëNW¤î¤NLÊA+I/çênPrSبAùJmÅ¥›.“*¥{Ö,µÍó³¥ülž÷âåÑR~¦éiÇÉ+êü­xš’zEÑ÷É8hýxxPa5n:áLç+q{cѧk¨ÔÏK½¿Ž¯Ò•¤×ð{Й4œ)îi©á¢Ã ͯqÐJÒËyZj‹|ªq16áMÏæšFãâ[VËÌÉLïÆT¶:^•’«Ü=+Njv©3Ň ”ºIÙU´Ù™É\Ÿ4DžcíM¼Ø6¹¹KCj±FÑ\wôV„’ØæhFÕA >ƒV’^ÎpjOR§!Ÿ>g¢Ÿ¹}þ¾~|w1jîâCi±­GJÌo9#gÆAË¥‡KQö<}n>CًÉL:|оI ùêäšOžéË{Âû…•­*òÔ=VóÜI÷ ›7ŽrÜ mÞ1æcÐÓ{ÔêÃœþՏÅr}Eo>4Ç9f–맇—W÷G³O·:ÉN<Þéx™Çð1£ó•8h¹ž(‡Ž?Ýgå3ù¯­¯^-§ÅÅt‘˜㠕¤—sOÞ)QJŽ[¹Qr`n€%6—º<»œxՁqÐJÒËùpWßv¹ó"Dã+qÐr—œÝ6UŠE >øñè|9¯ï4SܙâÎc¹ô´ÔXöAòü>¤+ىšêÁÂ]2%j™sÐrŸH­–)ѤD-sZ.•¼Åj™¦p¼Ü«ç!]IÞ9‡î¦®µÌ9h%éåÜÝ'—’µìáÊà qõëèáZc: ¡ søWî‡Þöäî1{j2Z÷)ÈÖz|¯(Ë&ñn.2ꘂ¯#ç+qmrW©}i)é†óøsZ.ÝÝefx
+#å!KW’^?,ï£Û—–—ò3•8H¯Ç3™e{ù×ÑëÆ}s’ýcºí©ÔÃŒûº Û¶ÜS%MuÒçD}bÜÿDC| `þ ꍢò›tÑÆærZþ«‘4`¨;0Ÿ$¼H0ÓõÍÏ3]¸WW¥º<p“/o_Îûë;w¤¸#ÅX.=<µé¹™)¿Yº’Ø‰?ªÍt¼æòpqW}k’»‡¹„Äûd!=æK›mu¶ßVw ©^—uvÖ9(œFª;ôä>b–ÜJ|–Ôx˜û…̲j
+GÊC–®$½¼ÜÇËÊ3^QÊÏTâ }Ÿš/®š‡
+I¹¶X)DKZ¹¶yùwŠ•r@‹z¬”k>¥!-B,–†ŒÐf±4dF,–†D­òX)DKZs­b<µNÍ5‘ºÍ¢3[Ç,ÿN±²ïQ‰à¹Æ± ;ÓÙ÷Gˆ”{`‘ÊciޙÁ•C¨Íb%mGM!®­Ey,–†ìQ‹¥!g
+Ùs­ÚSíµXR#û£öîé]°X9d2$¿ 8êŞÜ|XtFÞxªán;þ·ýKˆû”R!8÷™On‡?ß3Dc±bÓðx„ôôœ3îyíKˆÿ·×íÌ|¤ý73Þú#’þ³´‰“*˜·±=C6ÿÍ(Ùn#YgdëtÌÉ3DÙCš·Êsòô Eˆ¿ KCf
+y¤ƒkÚæ#¤R÷;ÅÒØ·1¤æ0d¼Þ)VÒ6¶2rFÒ6¶œë±GFË%)×cÏÖQmKCŠ=Ÿˆ¥!›µ+‡Œ°µ¶ϒZ,†p‚‹Úö–-Š /͛ÅҐå±X ÿ¨…Œ\ž‘Jj±4dŒGIG²ÛxԃÃû’›÷üL3êΑú’¾Í–B܍ç›RÛ|ØïœÖ*‹¥!3j•ÅÊ!´µÅJÚ´VY¬”ƒ‘´y­B~Ô+•t¤\»EQnÕf±4dX¬’-jÛDyê-B
+¶ XIÕcõXÒRÈñÐVBÛö°5ZrÚºäqU§?¶ÚÚbåÚú|ؚý–BFÎÁHÚÌÖÌÏØ#f–a¤\=[‡Ú<C`+æÀcådÑf!5Z>L…ÝjÔQ¥!-ìVs-Õ¿A#–†·›ÇJ!Z‹•´!^ŽwJh3çú葃£ä’{äú°ò´‘BÒ7Æ3äi±…Ýú÷}
++*µyžÒ•¤R
+1M—•ò3•8ˆ‹}¸Ynv³o|Q<¶u4Kð•8HZÆý4é~˜®ÝÍ|%Z.ÅKg›l˜×ٜƒV’"g»Ç˜¦kÌȃq+SÁõ=l‘ËQ½T–Kø†îb[Çciƒ¯ÄAh›K‹ë*Þ:_‰ƒ–KçKuÉAbLáØ"éJRè=-Ë3_QÊÏTâ m‘q碶ÈÅãMZ;}êlëX[‚¯ÄAh›K‹ë*Ñ_‰ƒ–KÇKu‰Ó S@m ZI
+MAÍâ´’93³hÙú+Jù™J¤fÙ£É=öhrÉÒL»5¹G&×ùJ´ÔA^¥Öä’Òݜ–šqÐr)n÷´&—)°ÉuZIŠRX“«eë¯(åg*q¾D%õD%õDÅ{¢â=іz¢-õDÛüC*óæ=Ñæ=іz¢-õD›÷D[ê‰6ï‰6Ômó«t%)Já=Qñž¨¤ž¨xOTf¸{‚=шiDcqðßu²€÷œjOä|%W¬ƒRÚL‰7©_‰ƒ–I¥÷ ®iw­jOä´’¥(Ã&@£”Ÿ©ÄAÙ,ì‰FL#3‹_ÿª=‘ó•8ÈÍBi3]¤3Ì¢©¹Yj5³È³f
+쉜ƒV’ºYÃ&@£”Ÿ©ÄA4Kókkók•ï{…ï— ây£6ÿÁWâ %ÒêÒÍuù¤eð•8h¹t©®»Nk
+qº®3ò`”Í‚—HƒŽf‘ƒ·©ú¨–8^¢à+q›Ò9M×ôIËà+q›å®øªkºágz4éJR7 cœ®ëŒ<qÇüÙäGÈFPù«CZgÓYà~Æ&7øJd—PJ¿–Óhêå##R3Z.Ýõòi:54¹ÁA+I‘³î1Óe¥üL%JfÑæõ”Æ0‹tªT--d|%2³PZ‡éaKÍ8h¹Ô̂Cå™ÂfyJW’šY4Æaº¬”Ÿ©ÄAz½ÍQ½mñ©o,× m:Ë»·-ÎWâ ¹\ÀÖ® Ïö ®Íßkç+qÐ2©´Ã֒5¶-ÎA+I¡wZ ›¤ˆR~¦e³°m11d¼›YŽj‰ÓÎÎWâ 7 ¥›ëÚü½v¾¹Y¤=¶ó@S˜éÑ<¤+IÝ,ˆaSZQÊÏT⠚¥uÿ&ºÙ¿‰Œåΐ®c‘¢·¡Â,ÎWâ ¹=¤í.m¦«ù7Qð•8h™TŠB]R<¦@³8­$E)ŠÅèÝtõy0ÊfáKÄ ½–ÊNÄSÕÅ/)K|‰œƒÜ,”6ÓÕü›(øJäf©ÕÌ"/SàKä´’Ô͂½›®Þ#ÆA0ËÿñãÿZÛS=endstream
+endobj
+6 0 obj
+17999
+endobj
+4 0 obj
+<</Type/Page/MediaBox [0 0 612 792]
+/Rotate 0/Parent 3 0 R
+/Resources<</ProcSet[/PDF]
+/ExtGState 8 0 R
+>>
+/Contents 5 0 R
+>>
+endobj
+3 0 obj
+<< /Type /Pages /Kids [
+4 0 R
+] /Count 1
+/Rotate 0>>
+endobj
+1 0 obj
+<</Type /Catalog /Pages 3 0 R
+>>
+endobj
+7 0 obj
+<</Type/ExtGState
+/OPM 1>>endobj
+8 0 obj
+<</R7
+7 0 R>>
+endobj
+2 0 obj
+<</Producer(GPL Ghostscript 8.15)
+/CreationDate(D:20070312220102)
+/ModDate(D:20070312220102)
+/Title(BOARD.bin)
+/Creator(PScript5.dll Version 5.2)
+/Author(Jakub)>>endobj
+xref
+0 9
+0000000000 65535 f
+0000018313 00000 n
+0000018431 00000 n
+0000018245 00000 n
+0000018105 00000 n
+0000000015 00000 n
+0000018084 00000 n
+0000018361 00000 n
+0000018402 00000 n
+trailer
+<< /Size 9 /Root 1 0 R /Info 2 0 R
+/ID [(ý*iš@kŒìïǃ¼þ)(ý*iš@kŒìïǃ¼þ)]
+>>
+startxref
+18608
+%%EOF
/roboti/istrobot/camerus/HW/CAM_PROFI/BOARD.PHO
0,0 → 1,315
*
*
G04 PADS Layout (Build Number 2006.45.1) generated Gerber (RS-274-X) file*
G04 PC Version=2.1*
*
%IN "LEDpanel.pcb"*%
*
%MOIN*%
*
%FSLAX35Y35*%
*
*
*
*
G04 PC Standard Apertures*
*
*
G04 Thermal Relief Aperture macro.*
%AMTER*
1,1,$1,0,0*
1,0,$1-$2,0,0*
21,0,$3,$4,0,0,45*
21,0,$3,$4,0,0,135*
%
*
*
G04 Annular Aperture macro.*
%AMANN*
1,1,$1,0,0*
1,0,$2,0,0*
%
*
*
G04 Odd Aperture macro.*
%AMODD*
1,1,$1,0,0*
1,0,$1-0.005,0,0*
%
*
*
G04 PC Custom Aperture Macros*
*
*
*
*
*
*
G04 PC Aperture Table*
*
%ADD024C,0.001*%
%ADD025C,0.01*%
*
*
*
*
G04 PC Copper Outlines (0)*
G04 Layer Name LEDpanel.pcb - dark (0)*
%LPD*%
*
*
G04 PC Area=Custom_Thermal*
*
G04 PC Custom Flashes*
G04 Layer Name LEDpanel.pcb - flashes*
%LPD*%
*
*
G04 PC Circuitry*
G04 Layer Name LEDpanel.pcb - circuitry*
%LPD*%
*
G54D24*
G01X120000Y179100D02*
X120003D01*
X651200D02*
X651203D01*
X651200Y120000D02*
X651203D01*
X651200Y179100D02*
X651203D01*
G54D25*
X120000D02*
X651200D01*
Y120000*
X120000*
Y179100*
Y212000D02*
X367827D01*
X120000D02*
X130000Y214500D01*
Y209500*
X120000Y212000*
X651200D02*
X403373D01*
X651200D02*
X641200Y209500D01*
Y214500*
X651200Y212000*
X120000Y184100D02*
Y217000D01*
X651200Y184100D02*
Y217000D01*
X373782Y214812D02*
X371509D01*
X371509D02*
X371282Y212000D01*
X371509Y212312*
X371509D02*
X372191Y212625D01*
X372873*
X373555Y212312*
X373555D02*
X374009Y211687D01*
X374009D02*
X374236Y210750D01*
X374009Y210125*
X373782Y209187*
X373782D02*
X373327Y208562D01*
X373327D02*
X372645Y208250D01*
X371964*
X371282Y208562*
X371282D02*
X371055Y208875D01*
X370827Y209500*
X376736Y214812D02*
X379236D01*
X379236D02*
X377873Y212312D01*
X377873D02*
X378555D01*
X378555D02*
X379009Y212000D01*
X379236Y211687*
X379236D02*
X379464Y210750D01*
Y210125*
X379236Y209187*
X379236D02*
X378782Y208562D01*
X378782D02*
X378100Y208250D01*
X377418*
X376736Y208562*
X376736D02*
X376509Y208875D01*
X376282Y209500*
X381509Y213562D02*
X381964Y213875D01*
X382645Y214812*
X382645D02*
Y208250D01*
X384918Y213250D02*
Y213562D01*
X384918D02*
X385145Y214187D01*
X385145D02*
X385373Y214500D01*
X385827Y214812*
X385827D02*
X386736D01*
X386736D02*
X387191Y214500D01*
X387418Y214187*
X387418D02*
X387645Y213562D01*
X387645D02*
Y212937D01*
X387645D02*
X387418Y212312D01*
X387418D02*
X386964Y211375D01*
X384691Y208250*
X387873*
X389918Y212625D02*
Y208250D01*
Y211375D02*
X390600Y212312D01*
X390600D02*
X391055Y212625D01*
X391736*
X392191Y212312*
X392191D02*
X392418Y211375D01*
Y208250*
Y211375D02*
X393100Y212312D01*
X393100D02*
X393555Y212625D01*
X394236*
X394691Y212312*
X394691D02*
X394918Y211375D01*
Y208250*
X396964Y214812D02*
X397191Y214500D01*
X397418Y214812*
X397418D02*
X397191Y215125D01*
X396964Y214812*
X397191Y212625D02*
Y208250D01*
X399464Y214812D02*
Y208250D01*
X672000Y120000D02*
Y142800D01*
Y120000D02*
X669500Y130000D01*
X674500*
X672000Y120000*
Y179100D02*
Y156300D01*
Y179100D02*
X674500Y169100D01*
X669500*
X672000Y179100*
X656200Y120000D02*
X677000D01*
X656200Y179100D02*
X677000D01*
X662909Y152362D02*
X660636D01*
X660636D02*
X660409Y149550D01*
X660636Y149862*
X660636D02*
X661318Y150175D01*
X662000*
X662682Y149862*
X662682D02*
X663136Y149237D01*
X663136D02*
X663364Y148300D01*
X663136Y147675*
X662909Y146737*
X662909D02*
X662455Y146112D01*
X662455D02*
X661773Y145800D01*
X661091*
X660409Y146112*
X660409D02*
X660182Y146425D01*
X659955Y147050*
X668364Y150175D02*
X668136Y149237D01*
X668136D02*
X667682Y148612D01*
X667682D02*
X667000Y148300D01*
X666773*
X666091Y148612*
X666091D02*
X665636Y149237D01*
X665636D02*
X665409Y150175D01*
Y150487*
X665409D02*
X665636Y151425D01*
X666091Y152050*
X666773Y152362*
X666773D02*
X667000D01*
X667000D02*
X667682Y152050D01*
X668136Y151425*
X668364Y150175*
Y148612*
X668364D02*
X668136Y147050D01*
X667682Y146112*
X667682D02*
X667000Y145800D01*
X666545*
X665864Y146112*
X665864D02*
X665636Y146737D01*
X670409Y151112D02*
X670864Y151425D01*
X671545Y152362*
X671545D02*
Y145800D01*
X673591Y150175D02*
Y145800D01*
Y148925D02*
X674273Y149862D01*
X674273D02*
X674727Y150175D01*
X675409*
X675864Y149862*
X675864D02*
X676091Y148925D01*
Y145800*
Y148925D02*
X676773Y149862D01*
X676773D02*
X677227Y150175D01*
X677909*
X678364Y149862*
X678364D02*
X678591Y148925D01*
Y145800*
X680636Y152362D02*
X680864Y152050D01*
X681091Y152362*
X681091D02*
X680864Y152675D01*
X680636Y152362*
X680864Y150175D02*
Y145800D01*
X683136Y152362D02*
Y145800D01*
X0Y0D02*
M02*
/roboti/istrobot/camerus/HW/CAM_PROFI/BOARD.rep
0,0 → 1,13
 
 
Photo-Plotter Apertures Report
==============================
Position Width Hgt/ID Shape Qty
======== ===== ====== ===== ===
24 1 0 RND 4
25 10 0 RND 26
 
 
 
 
 
/roboti/istrobot/camerus/HW/CAM_PROFI/DRILL.DRL
0,0 → 1,43
%
T1C.035F197S55
X014Y014506
X014Y015494
X01946Y015494
X01946Y014506
X022219Y013728
X022219Y017228
X02492Y015494
X02492Y014506
X03038Y014506
X03038Y015494
X033113Y017228
X033113Y013728
X03584Y014506
X03584Y015494
X038509Y016198
X037509Y016198
X0381Y0142
X0391Y0142
X0413Y014506
X0413Y015494
X039509Y016198
X043339Y017228
X043339Y013728
X044675Y013728
X044675Y017228
X04676Y015494
X04676Y014506
X05222Y014506
X05222Y015494
X054953Y017228
X054953Y013728
X05768Y014506
X05768Y015494
X06314Y015494
X06314Y014506
T2C.12598F035S794
X0168Y0134
X0278Y0136
X0494Y0134
X0604Y0134
M30
/roboti/istrobot/camerus/HW/CAM_PROFI/DRILL.lst
0,0 → 1,46
Drill Listing
=============
Drill: .035 Tool: 1 Feed: 197 Speed: 550
X 140000 Y 145062
X 140000 Y 154937
X 194600 Y 154937
X 194600 Y 145062
X 222186 Y 137284
X 222186 Y 172284
X 249200 Y 154937
X 249200 Y 145062
X 303800 Y 145062
X 303800 Y 154937
X 331129 Y 172284
X 331129 Y 137284
X 358400 Y 145062
X 358400 Y 154937
X 385087 Y 161979
X 375087 Y 161979
X 381000 Y 142000
X 391000 Y 142000
X 413000 Y 145062
X 413000 Y 154937
X 395087 Y 161979
X 433392 Y 172284
X 433392 Y 137284
X 446753 Y 137284
X 446753 Y 172284
X 467600 Y 154937
X 467600 Y 145062
X 522200 Y 145062
X 522200 Y 154937
X 549530 Y 172284
X 549530 Y 137284
X 576800 Y 145062
X 576800 Y 154937
X 631400 Y 154937
X 631400 Y 145062
 
Drill: .12598 Tool: 2 Feed: 35 Speed: 794
X 168000 Y 134000
X 278000 Y 136000
X 494000 Y 134000
X 604000 Y 134000
 
End of Listing
/roboti/istrobot/camerus/HW/CAM_PROFI/DRILL.rep
0,0 → 1,13
 
 
Drill Sizes Report
==================
Tool Size Pltd Feed Speed Qty
==== ==== ==== ==== ===== ===
1 35 x 197 550 35
2 125.98 x 35 794 4
 
 
 
 
 
/roboti/istrobot/camerus/HW/CAM_PROFI/V2.PHO
0,0 → 1,1574
*
*
G04 PADS Layout (Build Number 2006.45.1) generated Gerber (RS-274-X) file*
G04 PC Version=2.1*
*
%IN "LEDpanel.pcb"*%
*
%MOIN*%
*
%FSLAX35Y35*%
*
*
*
*
G04 PC Standard Apertures*
*
*
G04 Thermal Relief Aperture macro.*
%AMTER*
1,1,$1,0,0*
1,0,$1-$2,0,0*
21,0,$3,$4,0,0,45*
21,0,$3,$4,0,0,135*
%
*
*
G04 Annular Aperture macro.*
%AMANN*
1,1,$1,0,0*
1,0,$2,0,0*
%
*
*
G04 Odd Aperture macro.*
%AMODD*
1,1,$1,0,0*
1,0,$1-0.005,0,0*
%
*
*
G04 PC Custom Aperture Macros*
*
*
*
*
*
*
G04 PC Aperture Table*
*
%ADD012R,0.07X0.07*%
%ADD013C,0.23622*%
%ADD025C,0.01*%
%ADD031C,0.07*%
%ADD042C,0.045*%
%ADD043R,0.066X0.066*%
%ADD044C,0.066*%
%ADD045R,0.065X0.065*%
%ADD046C,0.08268*%
%ADD047C,0.035*%
%ADD048C,0.025*%
*
*
*
*
G04 PC Copper Outlines (0)*
G04 Layer Name LEDpanel.pcb - dark (0)*
%LPD*%
*
*
G04 PC Area=ANP000000*
G75*
G36*
G01*
X648700Y123000D02*
Y176100D01*
G03*
X648200Y176600I-500J-0D01*
G01*
X555558D01*
G03*
X555136Y175833I0J-500D01*
G02*
X545345Y167138I-5606J-3548D01*
G03*
X545029Y167250I-316J-388D01*
G01*
X451254D01*
G03*
X450939Y167138I0J-500D01*
G02*
X442568I-4186J5147D01*
G03*
X442252Y167250I-316J-388D01*
G01*
X437893D01*
G03*
X437578Y167138I0J-500D01*
G02*
X429207I-4186J5147D01*
G03*
X428891Y167250I-316J-388D01*
G01*
X400923D01*
G03*
X400492Y166497I0J-500D01*
G02*
X400837Y165229I-2155J-1268D01*
G01*
Y158729D01*
G02*
X398337Y156229I-2500J0D01*
G01*
X391837D01*
G02*
X390587Y156564I0J2500D01*
G03*
X389837Y156131I-250J-433D01*
G01*
Y151057D01*
G03*
X389984Y150703I500J-0D01*
G01*
X392541Y148146D01*
G03*
X392894Y148000I353J354D01*
G01*
X394500D01*
G02*
X397000Y145500I0J-2500D01*
G01*
Y138750D01*
G03*
X397500Y138250I500J0D01*
G01*
X399969D01*
G03*
X400323Y138396I0J500D01*
G01*
X407054Y145127D01*
G03*
X407200Y145481I-354J354D01*
G01*
Y148363D01*
G02*
X408401Y150499I2500J-0D01*
G03*
X408527Y151245I-260J427D01*
G02*
X417600Y158470I4473J3692D01*
G03*
X417643Y158421I397J304D01*
G01*
X425022Y151042D01*
G03*
X425204Y150926I354J353D01*
G02*
X426748Y149940I-1462J-3991D01*
G01*
X432634Y144054D01*
G03*
X433016Y143908I353J353D01*
G02*
X439605Y139612I376J-6623D01*
G03*
X440541I468J175D01*
G02*
X447130Y143908I6212J-2327D01*
G03*
X447512Y144054I28J499D01*
G01*
X452463Y149005D01*
G02*
X454579Y150156I3005J-3005D01*
G03*
X454827Y150291I-105J489D01*
G01*
X462957Y158421D01*
G03*
X463000Y158470I-354J353D01*
G02*
X472073Y151245I4600J-3533D01*
G03*
X472199Y150499I386J-319D01*
G02*
X473089Y149571I-1299J-2136D01*
G03*
X473526Y149313I437J242D01*
G01*
X476186D01*
G03*
X476539Y149459I-0J500D01*
G01*
X485022Y157942D01*
G02*
X488027Y159187I3005J-3005D01*
G01*
X518061D01*
G03*
X518390Y159310I0J500D01*
G02*
X526673Y151245I3810J-4373D01*
G03*
X526799Y150499I386J-319D01*
G02*
X528000Y148363I-1299J-2136D01*
G01*
Y141763D01*
G02*
X525500Y139263I-2500J-0D01*
G01*
X518900D01*
G02*
X516400Y141763I0J2500D01*
G01*
Y148363D01*
G02*
X516915Y149883I2500J-0D01*
G03*
X516518Y150687I-397J304D01*
G01*
X489995D01*
G03*
X489641Y150541I-0J-500D01*
G01*
X481158Y142058D01*
G02*
X478153Y140813I-3005J3005D01*
G01*
X473526D01*
G03*
X473089Y140555I0J-500D01*
G02*
X470900Y139263I-2189J1208D01*
G01*
X464300D01*
G02*
X461800Y141763I0J2500D01*
G01*
Y144036D01*
G03*
X460946Y144389I-500J-0D01*
G01*
X459552Y142995D01*
G02*
X457437Y141844I-3005J3005D01*
G03*
X457188Y141709I104J-489D01*
G01*
X453522Y138043D01*
G03*
X453376Y137661I354J-353D01*
G02*
X440541Y134958I-6623J-376D01*
G03*
X439605I-468J-176D01*
G02*
X426769Y137661I-6213J2327D01*
G03*
X426623Y138043I-499J29D01*
G01*
X421839Y142828D01*
G03*
X421657Y142944I-354J-354D01*
G02*
X420113Y143930I1462J3991D01*
G01*
X419654Y144389D01*
G03*
X418800Y144036I-354J-353D01*
G01*
Y141763D01*
G02*
X416300Y139263I-2500J-0D01*
G01*
X413418D01*
G03*
X413064Y139117I-0J-500D01*
G01*
X404942Y130995D01*
G02*
X401937Y129750I-3005J3005D01*
G01*
X378747D01*
G02*
X375742Y130995I-0J4250D01*
G01*
X366995Y139742D01*
G02*
X365750Y142747I3005J3005D01*
G01*
Y143486D01*
G03*
X365604Y143839I-500J-0D01*
G01*
X365054Y144389D01*
G03*
X364200Y144036I-354J-353D01*
G01*
Y141763D01*
G02*
X361700Y139263I-2500J-0D01*
G01*
X355100D01*
G02*
X352600Y141763I0J2500D01*
G01*
Y148363D01*
G02*
X353801Y150499I2500J-0D01*
G03*
X353927Y151245I-260J427D01*
G02*
X363000Y158470I4473J3692D01*
G03*
X363043Y158421I397J304D01*
G01*
X373005Y148459D01*
G02*
X374250Y145453I-3005J-3006D01*
G01*
Y144714D01*
G03*
X374396Y144361I500J0D01*
G01*
X380361Y138396D01*
G03*
X380714Y138250I353J354D01*
G01*
X384500D01*
G03*
X385000Y138750I-0J500D01*
G01*
Y142045D01*
G03*
X384854Y142398I-500J-0D01*
G01*
X381728Y145523D01*
G02*
X380337Y148882I3359J3359D01*
G01*
Y156131D01*
G03*
X379587Y156564I-500J0D01*
G02*
X378337Y156229I-1250J2165D01*
G01*
X371837D01*
G02*
X369337Y158729I0J2500D01*
G01*
Y165229D01*
G02*
X369841Y166734I2500J0D01*
G03*
X369441Y167535I-400J301D01*
G01*
X335959D01*
G03*
X335621Y167403I0J-500D01*
G02*
X326638I-4492J4882D01*
G03*
X326299Y167535I-339J-368D01*
G01*
X227016D01*
G03*
X226678Y167403I0J-500D01*
G02*
X216581Y175833I-4492J4882D01*
G03*
X216158Y176600I-423J267D01*
G01*
X123000D01*
G03*
X122500Y176100I0J-500D01*
G01*
Y123000D01*
G03*
X123000Y122500I500J0D01*
G01*
X648200D01*
G03*
X648700Y123000I-0J500D01*
G37*
G74*
*
*
G04 PC Void Outlines (0)*
G04 Layer Name LEDpanel.pcb - clear (0)*
%LPC*%
*
*
G04 PC Area=ANP000000*
G75*
G36*
G01*
X627590Y159310D02*
G02*
X635873Y151245I3810J-4373D01*
G03*
X635999Y150499I386J-319D01*
G02*
X637200Y148363I-1299J-2136D01*
G01*
Y141763D01*
G02*
X634700Y139263I-2500J-0D01*
G01*
X628100D01*
G02*
X625600Y141763I0J2500D01*
G01*
Y148363D01*
G02*
X626115Y149883I2500J-0D01*
G03*
X625718Y150687I-397J304D01*
G01*
X599595D01*
G03*
X599241Y150541I-0J-500D01*
G01*
X590758Y142058D01*
G02*
X587753Y140813I-3005J3005D01*
G01*
X582726D01*
G03*
X582289Y140555I0J-500D01*
G02*
X580100Y139263I-2189J1208D01*
G01*
X573500D01*
G02*
X571000Y141763I0J2500D01*
G01*
Y148363D01*
G02*
X571515Y149883I2500J-0D01*
G03*
X571118Y150687I-397J304D01*
G01*
X569150D01*
G03*
X568796Y150541I-0J-500D01*
G01*
X556299Y138043D01*
G03*
X556153Y137661I353J-353D01*
G02*
X549907Y143908I-6623J-376D01*
G03*
X550288Y144054I28J499D01*
G01*
X564177Y157942D01*
G02*
X567182Y159187I3005J-3005D01*
G01*
X572661D01*
G03*
X572990Y159310I0J500D01*
G02*
X581273Y151245I3810J-4373D01*
G03*
X581399Y150499I386J-319D01*
G02*
X582289Y149571I-1299J-2136D01*
G03*
X582726Y149313I437J242D01*
G01*
X585786D01*
G03*
X586139Y149459I-0J500D01*
G01*
X594622Y157942D01*
G02*
X597627Y159187I3005J-3005D01*
G01*
X627261D01*
G03*
X627590Y159310I0J500D01*
G37*
G74*
*
G75*
G36*
G01*
X617000Y172750D02*
Y163750D01*
G02*
X614500Y161250I-2500J0D01*
G01*
X585682D01*
G02*
X583182Y163750I-0J2500D01*
G01*
Y172750D01*
G02*
X585682Y175250I2500J0D01*
G01*
X614500D01*
G02*
X617000Y172750I0J-2500D01*
G37*
G74*
*
G75*
G36*
G01*
X330753Y143908D02*
G02*
X324506Y137661I376J-6623D01*
G03*
X324361Y138043I-499J29D01*
G01*
X311863Y150541D01*
G03*
X311510Y150687I-353J-354D01*
G01*
X309482D01*
G03*
X309085Y149883I-0J-500D01*
G02*
X309600Y148363I-1985J-1520D01*
G01*
Y141763D01*
G02*
X307100Y139263I-2500J-0D01*
G01*
X300500D01*
G02*
X298311Y140555I0J2500D01*
G03*
X297874Y140813I-437J-242D01*
G01*
X294547D01*
G02*
X291542Y142058I-0J4250D01*
G01*
X283059Y150541D01*
G03*
X282705Y150687I-354J-354D01*
G01*
X254882D01*
G03*
X254485Y149883I-0J-500D01*
G02*
X255000Y148363I-1985J-1520D01*
G01*
Y141763D01*
G02*
X252500Y139263I-2500J-0D01*
G01*
X245900D01*
G02*
X243400Y141763I0J2500D01*
G01*
Y148363D01*
G02*
X244601Y150499I2500J-0D01*
G03*
X244727Y151245I-260J427D01*
G02*
X253010Y159310I4473J3692D01*
G03*
X253339Y159187I329J377D01*
G01*
X284673D01*
G02*
X287678Y157942I-0J-4250D01*
G01*
X296161Y149459D01*
G03*
X296514Y149313I353J354D01*
G01*
X297874D01*
G03*
X298311Y149571I-0J500D01*
G02*
X299201Y150499I2189J-1208D01*
G03*
X299327Y151245I-260J427D01*
G02*
X307610Y159310I4473J3692D01*
G03*
X307939Y159187I329J377D01*
G01*
X313477D01*
G02*
X316482Y157942I0J-4250D01*
G01*
X330371Y144054D01*
G03*
X330753Y143908I354J353D01*
G37*
G74*
*
G75*
G36*
G01*
X221810D02*
G02*
X215563Y137661I376J-6623D01*
G03*
X215417Y138043I-499J29D01*
G01*
X202920Y150541D01*
G03*
X202566Y150687I-354J-354D01*
G01*
X200282D01*
G03*
X199885Y149883I-0J-500D01*
G02*
X200400Y148363I-1985J-1520D01*
G01*
Y141763D01*
G02*
X197900Y139263I-2500J-0D01*
G01*
X191300D01*
G02*
X189111Y140555I0J2500D01*
G03*
X188674Y140813I-437J-242D01*
G01*
X183947D01*
G02*
X180942Y142058I-0J4250D01*
G01*
X172459Y150541D01*
G03*
X172105Y150687I-354J-354D01*
G01*
X145682D01*
G03*
X145285Y149883I-0J-500D01*
G02*
X145800Y148363I-1985J-1520D01*
G01*
Y141763D01*
G02*
X143300Y139263I-2500J-0D01*
G01*
X136700D01*
G02*
X134200Y141763I0J2500D01*
G01*
Y148363D01*
G02*
X135401Y150499I2500J-0D01*
G03*
X135527Y151245I-260J427D01*
G02*
X141719Y160476I4473J3692D01*
G03*
X141850Y160454I148J478D01*
X141967Y160393I287J410D01*
G02*
X143810Y159310I-1967J-5456D01*
G03*
X144139Y159187I329J377D01*
G01*
X174073D01*
G02*
X177078Y157942I-0J-4250D01*
G01*
X185561Y149459D01*
G03*
X185914Y149313I353J354D01*
G01*
X188674D01*
G03*
X189111Y149571I-0J500D01*
G02*
X190001Y150499I2189J-1208D01*
G03*
X190127Y151245I-260J427D01*
G02*
X198410Y159310I4473J3692D01*
G03*
X198739Y159187I329J377D01*
G01*
X204534D01*
G02*
X207539Y157942I-0J-4250D01*
G01*
X221428Y144054D01*
G03*
X221810Y143908I353J353D01*
G37*
G74*
*
G75*
G36*
G01*
X189000Y172750D02*
Y163750D01*
G02*
X186500Y161250I-2500J0D01*
G01*
X142955D01*
G02*
X142273Y161345I-0J2500D01*
G03*
X142154Y161363I-136J-481D01*
X142048Y161420I-287J-409D01*
G02*
X140455Y163750I907J2330D01*
G01*
Y172750D01*
G02*
X142955Y175250I2500J0D01*
G01*
X186500D01*
G02*
X189000Y172750I0J-2500D01*
G37*
G74*
*
*
G04 PC Copper Outlines (1)*
G04 Layer Name LEDpanel.pcb - dark (1)*
%LPD*%
*
*
G04 PC Area=Custom_Thermal*
*
G04 PC Custom Flashes*
G04 Layer Name LEDpanel.pcb - flashes*
%LPD*%
*
*
G04 PC Circuitry*
G04 Layer Name LEDpanel.pcb - circuitry*
%LPD*%
*
G54D12*
G01X391000Y142000D03*
G54D13*
X604000Y134000D03*
X168000D03*
X278000Y136000D03*
X494000Y134000D03*
G54D25*
X614000Y171250D02*
Y166000D01*
X611818*
X610182Y171250D02*
Y166000D01*
Y171250D02*
X607818D01*
X610182Y168750D02*
X608727D01*
X610182Y166000D02*
X607818D01*
X606182Y171250D02*
Y166000D01*
Y171250D02*
X604909D01*
X604364Y171000*
X604000Y170500*
X603818Y170000*
X603636Y169250*
Y168000*
X603818Y167250*
X604000Y166750*
X604364Y166250*
X604909Y166000*
X606182*
X602000Y169500D02*
Y164250D01*
Y168750D02*
X601636Y169250D01*
X601273Y169500*
X600727*
X600364Y169250*
X600000Y168750*
X599818Y168000*
Y167500*
X600000Y166750*
X600364Y166250*
X600727Y166000*
X601273*
X601636Y166250*
X602000Y166750*
X596000Y169500D02*
Y166000D01*
Y168750D02*
X596364Y169250D01*
X596727Y169500*
X597273*
X597636Y169250*
X598000Y168750*
X598182Y168000*
Y167500*
X598000Y166750*
X597636Y166250*
X597273Y166000*
X596727*
X596364Y166250*
X596000Y166750*
X594364Y169500D02*
Y166000D01*
Y168500D02*
X593818Y169250D01*
X593455Y169500*
X592909*
X592545Y169250*
X592364Y168500*
Y166000*
X590727Y168000D02*
X588545D01*
Y168500*
X588727Y169000*
X588909Y169250*
X589273Y169500*
X589818*
X590182Y169250*
X590545Y168750*
X590727Y168000*
Y167500*
X590545Y166750*
X590182Y166250*
X589818Y166000*
X589273*
X588909Y166250*
X588545Y166750*
X586909Y171250D02*
Y166000D01*
X186000Y171250D02*
Y166000D01*
X183455Y171250D02*
X186000Y167750D01*
X185091Y169000D02*
X183455Y166000D01*
X180364Y171250D02*
X181818Y166000D01*
X180364Y171250D02*
X178909Y166000D01*
X181273Y167750D02*
X179455D01*
X177273Y171250D02*
Y166000D01*
X174727Y171250D02*
X177273Y167750D01*
X176364Y169000D02*
X174727Y166000D01*
X173091Y171250D02*
Y166000D01*
X170909*
X169273Y171250D02*
Y166000D01*
X167636Y171250D02*
Y166000D01*
X165091Y171250D02*
X167636Y167750D01*
X166727Y169000D02*
X165091Y166000D01*
X159091Y170000D02*
Y170250D01*
X158909Y170750*
X158727Y171000*
X158364Y171250*
X157636*
X157273Y171000*
X157091Y170750*
X156909Y170250*
Y169750*
X157091Y169250*
X157455Y168500*
X159273Y166000*
X156727*
X154000Y171250D02*
X154545Y171000D01*
X154909Y170250*
X155091Y169000*
Y168250*
X154909Y167000*
X154545Y166250*
X154000Y166000*
X153636*
X153091Y166250*
X152727Y167000*
X152545Y168250*
Y169000*
X152727Y170250*
X153091Y171000*
X153636Y171250*
X154000*
X149818D02*
X150364Y171000D01*
X150727Y170250*
X150909Y169000*
Y168250*
X150727Y167000*
X150364Y166250*
X149818Y166000*
X149455*
X148909Y166250*
X148545Y167000*
X148364Y168250*
Y169000*
X148545Y170250*
X148909Y171000*
X149455Y171250*
X149818*
X144182D02*
X146000Y166000D01*
X146727Y171250D02*
X144182D01*
X648700Y123000D02*
Y176100D01*
G75*
G03X648200Y176600I-500J-0D01*
G01X555558*
G03X555136Y175833I0J-500*
G01X545345Y167138D02*
G03X555136Y175833I4185J5147D01*
G01X545345Y167138D02*
G03X545029Y167250I-316J-388D01*
G01X451254*
G03X450939Y167138I0J-500*
G01X442568D02*
G03X450939I4185J5147D01*
G01X442568D02*
G03X442252Y167250I-316J-388D01*
G01X437893*
G03X437578Y167138I0J-500*
G01X429207D02*
G03X437578I4185J5147D01*
G01X429207D02*
G03X428891Y167250I-316J-388D01*
G01X400923*
G03X400492Y166497I0J-500*
G01X400837Y165229D02*
G03X400492Y166497I-2500J0D01*
G01X400837Y165229D02*
Y158729D01*
X398337Y156229D02*
G03X400837Y158729I0J2500D01*
G01X398337Y156229D02*
X391837D01*
X390587Y156564D02*
G03X391837Y156229I1250J2165D01*
G01X390587Y156564D02*
G03X389837Y156131I-250J-433D01*
G01Y151057*
G03X389984Y150703I500J-0*
G01X392541Y148146*
G03X392894Y148000I353J354*
G01X394500*
X397000Y145500D02*
G03X394500Y148000I-2500J0D01*
G01X397000Y145500D02*
Y138750D01*
G03X397500Y138250I500J0*
G01X399969*
G03X400323Y138396I0J500*
G01X407054Y145127*
G03X407200Y145481I-354J354*
G01Y148363*
X408401Y150499D02*
G03X407200Y148363I1299J-2136D01*
G01X408401Y150499D02*
G03X408527Y151245I-260J427D01*
G01X417600Y158470D02*
G03X408527Y151245I-4600J-3533D01*
G01X417600Y158470D02*
G03X417643Y158421I397J304D01*
G01X425022Y151042*
G03X425204Y150926I354J353*
G01X426748Y149940D02*
G03X425204Y150926I-3006J-3005D01*
G01X426748Y149940D02*
X432634Y144054D01*
G03X433016Y143908I353J353*
G01X439605Y139612D02*
G03X433016Y143908I-6213J-2327D01*
G01X439605Y139612D02*
G03X440541I468J175D01*
G01X447130Y143908D02*
G03X440541Y139612I-377J-6623D01*
G01X447130Y143908D02*
G03X447512Y144054I28J499D01*
G01X452463Y149005*
X454579Y150156D02*
G03X452463Y149005I889J-4156D01*
G01X454579Y150156D02*
G03X454827Y150291I-105J489D01*
G01X462957Y158421*
G03X463000Y158470I-354J353*
G01X472073Y151245D02*
G03X463000Y158470I-4473J3692D01*
G01X472073Y151245D02*
G03X472199Y150499I386J-319D01*
G01X473089Y149571D02*
G03X472199Y150499I-2189J-1208D01*
G01X473089Y149571D02*
G03X473526Y149313I437J242D01*
G01X476186*
G03X476539Y149459I-0J500*
G01X485022Y157942*
X488027Y159187D02*
G03X485022Y157942I0J-4250D01*
G01X488027Y159187D02*
X518061D01*
G03X518390Y159310I0J500*
G01X526673Y151245D02*
G03X518390Y159310I-4473J3692D01*
G01X526673Y151245D02*
G03X526799Y150499I386J-319D01*
G01X528000Y148363D02*
G03X526799Y150499I-2500J-0D01*
G01X528000Y148363D02*
Y141763D01*
X525500Y139263D02*
G03X528000Y141763I0J2500D01*
G01X525500Y139263D02*
X518900D01*
X516400Y141763D02*
G03X518900Y139263I2500J-0D01*
G01X516400Y141763D02*
Y148363D01*
X516915Y149883D02*
G03X516400Y148363I1985J-1520D01*
G01X516915Y149883D02*
G03X516518Y150687I-397J304D01*
G01X489995*
G03X489641Y150541I-0J-500*
G01X481158Y142058*
X478153Y140813D02*
G03X481158Y142058I0J4250D01*
G01X478153Y140813D02*
X473526D01*
G03X473089Y140555I0J-500*
G01X470900Y139263D02*
G03X473089Y140555I0J2500D01*
G01X470900Y139263D02*
X464300D01*
X461800Y141763D02*
G03X464300Y139263I2500J-0D01*
G01X461800Y141763D02*
Y144036D01*
G03X460946Y144389I-500J-0*
G01X459552Y142995*
X457437Y141844D02*
G03X459552Y142995I-890J4156D01*
G01X457437Y141844D02*
G03X457188Y141709I104J-489D01*
G01X453522Y138043*
G03X453376Y137661I354J-353*
G01X440541Y134958D02*
G03X453376Y137661I6212J2327D01*
G01X440541Y134958D02*
G03X439605I-468J-176D01*
G01X426769Y137661D02*
G03X439605Y134958I6623J-376D01*
G01X426769Y137661D02*
G03X426623Y138043I-499J29D01*
G01X421839Y142828*
G03X421657Y142944I-354J-354*
G01X420113Y143930D02*
G03X421657Y142944I3006J3005D01*
G01X420113Y143930D02*
X419654Y144389D01*
G03X418800Y144036I-354J-353*
G01Y141763*
X416300Y139263D02*
G03X418800Y141763I0J2500D01*
G01X416300Y139263D02*
X413418D01*
G03X413064Y139117I-0J-500*
G01X404942Y130995*
X401937Y129750D02*
G03X404942Y130995I0J4250D01*
G01X401937Y129750D02*
X378747D01*
X375742Y130995D02*
G03X378747Y129750I3005J3005D01*
G01X375742Y130995D02*
X366995Y139742D01*
X365750Y142747D02*
G03X366995Y139742I4250J-0D01*
G01X365750Y142747D02*
Y143486D01*
G03X365604Y143839I-500J-0*
G01X365054Y144389*
G03X364200Y144036I-354J-353*
G01Y141763*
X361700Y139263D02*
G03X364200Y141763I0J2500D01*
G01X361700Y139263D02*
X355100D01*
X352600Y141763D02*
G03X355100Y139263I2500J-0D01*
G01X352600Y141763D02*
Y148363D01*
X353801Y150499D02*
G03X352600Y148363I1299J-2136D01*
G01X353801Y150499D02*
G03X353927Y151245I-260J427D01*
G01X363000Y158470D02*
G03X353927Y151245I-4600J-3533D01*
G01X363000Y158470D02*
G03X363043Y158421I397J304D01*
G01X373005Y148459*
X374250Y145453D02*
G03X373005Y148459I-4250J0D01*
G01X374250Y145453D02*
Y144714D01*
G03X374396Y144361I500J0*
G01X380361Y138396*
G03X380714Y138250I353J354*
G01X384500*
G03X385000Y138750I-0J500*
G01Y142045*
G03X384854Y142398I-500J-0*
G01X381728Y145523*
X380337Y148882D02*
G03X381728Y145523I4750J0D01*
G01X380337Y148882D02*
Y156131D01*
G03X379587Y156564I-500J0*
G01X378337Y156229D02*
G03X379587Y156564I0J2500D01*
G01X378337Y156229D02*
X371837D01*
X369337Y158729D02*
G03X371837Y156229I2500J0D01*
G01X369337Y158729D02*
Y165229D01*
X369841Y166734D02*
G03X369337Y165229I1996J-1505D01*
G01X369841Y166734D02*
G03X369441Y167535I-400J301D01*
G01X335959*
G03X335621Y167403I0J-500*
G01X326638D02*
G03X335621I4491J4882D01*
G01X326638D02*
G03X326299Y167535I-339J-368D01*
G01X227016*
G03X226678Y167403I0J-500*
G01X216581Y175833D02*
G03X226678Y167403I5605J-3548D01*
G01X216581Y175833D02*
G03X216158Y176600I-423J267D01*
G01X123000*
G03X122500Y176100I0J-500*
G01Y123000*
G03X123000Y122500I500J0*
G01X648200*
G03X648700Y123000I-0J500*
G01X635873Y151245D02*
G03X627590Y159310I-4473J3692D01*
G01X635873Y151245D02*
G03X635999Y150499I386J-319D01*
G01X637200Y148363D02*
G03X635999Y150499I-2500J-0D01*
G01X637200Y148363D02*
Y141763D01*
X634700Y139263D02*
G03X637200Y141763I0J2500D01*
G01X634700Y139263D02*
X628100D01*
X625600Y141763D02*
G03X628100Y139263I2500J-0D01*
G01X625600Y141763D02*
Y148363D01*
X626115Y149883D02*
G03X625600Y148363I1985J-1520D01*
G01X626115Y149883D02*
G03X625718Y150687I-397J304D01*
G01X599595*
G03X599241Y150541I-0J-500*
G01X590758Y142058*
X587753Y140813D02*
G03X590758Y142058I0J4250D01*
G01X587753Y140813D02*
X582726D01*
G03X582289Y140555I0J-500*
G01X580100Y139263D02*
G03X582289Y140555I0J2500D01*
G01X580100Y139263D02*
X573500D01*
X571000Y141763D02*
G03X573500Y139263I2500J-0D01*
G01X571000Y141763D02*
Y148363D01*
X571515Y149883D02*
G03X571000Y148363I1985J-1520D01*
G01X571515Y149883D02*
G03X571118Y150687I-397J304D01*
G01X569150*
G03X568796Y150541I-0J-500*
G01X556299Y138043*
G03X556153Y137661I353J-353*
G01X549907Y143908D02*
G03X556153Y137661I-377J-6623D01*
G01X549907Y143908D02*
G03X550288Y144054I28J499D01*
G01X564177Y157942*
X567182Y159187D02*
G03X564177Y157942I0J-4250D01*
G01X567182Y159187D02*
X572661D01*
G03X572990Y159310I0J500*
G01X581273Y151245D02*
G03X572990Y159310I-4473J3692D01*
G01X581273Y151245D02*
G03X581399Y150499I386J-319D01*
G01X582289Y149571D02*
G03X581399Y150499I-2189J-1208D01*
G01X582289Y149571D02*
G03X582726Y149313I437J242D01*
G01X585786*
G03X586139Y149459I-0J500*
G01X594622Y157942*
X597627Y159187D02*
G03X594622Y157942I0J-4250D01*
G01X597627Y159187D02*
X627261D01*
G03X627590Y159310I0J500*
G01X617000Y172750D02*
Y163750D01*
X614500Y161250D02*
G03X617000Y163750I0J2500D01*
G01X614500Y161250D02*
X585682D01*
X583182Y163750D02*
G03X585682Y161250I2500J0D01*
G01X583182Y163750D02*
Y172750D01*
X585682Y175250D02*
G03X583182Y172750I-0J-2500D01*
G01X585682Y175250D02*
X614500D01*
X617000Y172750D02*
G03X614500Y175250I-2500J0D01*
G01X324506Y137661D02*
G03X330753Y143908I6623J-376D01*
G01X324506Y137661D02*
G03X324361Y138043I-499J29D01*
G01X311863Y150541*
G03X311510Y150687I-353J-354*
G01X309482*
G03X309085Y149883I-0J-500*
G01X309600Y148363D02*
G03X309085Y149883I-2500J-0D01*
G01X309600Y148363D02*
Y141763D01*
X307100Y139263D02*
G03X309600Y141763I0J2500D01*
G01X307100Y139263D02*
X300500D01*
X298311Y140555D02*
G03X300500Y139263I2189J1208D01*
G01X298311Y140555D02*
G03X297874Y140813I-437J-242D01*
G01X294547*
X291542Y142058D02*
G03X294547Y140813I3005J3005D01*
G01X291542Y142058D02*
X283059Y150541D01*
G03X282705Y150687I-354J-354*
G01X254882*
G03X254485Y149883I-0J-500*
G01X255000Y148363D02*
G03X254485Y149883I-2500J-0D01*
G01X255000Y148363D02*
Y141763D01*
X252500Y139263D02*
G03X255000Y141763I0J2500D01*
G01X252500Y139263D02*
X245900D01*
X243400Y141763D02*
G03X245900Y139263I2500J-0D01*
G01X243400Y141763D02*
Y148363D01*
X244601Y150499D02*
G03X243400Y148363I1299J-2136D01*
G01X244601Y150499D02*
G03X244727Y151245I-260J427D01*
G01X253010Y159310D02*
G03X244727Y151245I-3810J-4373D01*
G01X253010Y159310D02*
G03X253339Y159187I329J377D01*
G01X284673*
X287678Y157942D02*
G03X284673Y159187I-3005J-3005D01*
G01X287678Y157942D02*
X296161Y149459D01*
G03X296514Y149313I353J354*
G01X297874*
G03X298311Y149571I-0J500*
G01X299201Y150499D02*
G03X298311Y149571I1299J-2136D01*
G01X299201Y150499D02*
G03X299327Y151245I-260J427D01*
G01X307610Y159310D02*
G03X299327Y151245I-3810J-4373D01*
G01X307610Y159310D02*
G03X307939Y159187I329J377D01*
G01X313477*
X316482Y157942D02*
G03X313477Y159187I-3005J-3005D01*
G01X316482Y157942D02*
X330371Y144054D01*
G03X330753Y143908I354J353*
G01X215563Y137661D02*
G03X221810Y143908I6623J-376D01*
G01X215563Y137661D02*
G03X215417Y138043I-499J29D01*
G01X202920Y150541*
G03X202566Y150687I-354J-354*
G01X200282*
G03X199885Y149883I-0J-500*
G01X200400Y148363D02*
G03X199885Y149883I-2500J-0D01*
G01X200400Y148363D02*
Y141763D01*
X197900Y139263D02*
G03X200400Y141763I0J2500D01*
G01X197900Y139263D02*
X191300D01*
X189111Y140555D02*
G03X191300Y139263I2189J1208D01*
G01X189111Y140555D02*
G03X188674Y140813I-437J-242D01*
G01X183947*
X180942Y142058D02*
G03X183947Y140813I3005J3005D01*
G01X180942Y142058D02*
X172459Y150541D01*
G03X172105Y150687I-354J-354*
G01X145682*
G03X145285Y149883I-0J-500*
G01X145800Y148363D02*
G03X145285Y149883I-2500J-0D01*
G01X145800Y148363D02*
Y141763D01*
X143300Y139263D02*
G03X145800Y141763I0J2500D01*
G01X143300Y139263D02*
X136700D01*
X134200Y141763D02*
G03X136700Y139263I2500J-0D01*
G01X134200Y141763D02*
Y148363D01*
X135401Y150499D02*
G03X134200Y148363I1299J-2136D01*
G01X135401Y150499D02*
G03X135527Y151245I-260J427D01*
G01X141719Y160476D02*
G03X135527Y151245I-1719J-5539D01*
G01X141719Y160476D02*
G03X141850Y160454I148J478D01*
X141967Y160393I287J410*
G01X143810Y159310D02*
G03X141967Y160393I-3810J-4373D01*
G01X143810Y159310D02*
G03X144139Y159187I329J377D01*
G01X174073*
X177078Y157942D02*
G03X174073Y159187I-3005J-3005D01*
G01X177078Y157942D02*
X185561Y149459D01*
G03X185914Y149313I353J354*
G01X188674*
G03X189111Y149571I-0J500*
G01X190001Y150499D02*
G03X189111Y149571I1299J-2136D01*
G01X190001Y150499D02*
G03X190127Y151245I-260J427D01*
G01X198410Y159310D02*
G03X190127Y151245I-3810J-4373D01*
G01X198410Y159310D02*
G03X198739Y159187I329J377D01*
G01X204534*
X207539Y157942D02*
G03X204534Y159187I-3005J-3005D01*
G01X207539Y157942D02*
X221428Y144054D01*
G03X221810Y143908I353J353*
G01X189000Y172750D02*
Y163750D01*
X186500Y161250D02*
G03X189000Y163750I0J2500D01*
G01X186500Y161250D02*
X142955D01*
X142273Y161345D02*
G03X142955Y161250I682J2405D01*
G01X142273Y161345D02*
G03X142154Y161363I-136J-481D01*
X142048Y161420I-287J-409*
G01X140455Y163750D02*
G03X142048Y161420I2500J0D01*
G01X140455Y163750D02*
Y172750D01*
X142955Y175250D02*
G03X140455Y172750I-0J-2500D01*
G01X142955Y175250D02*
X186500D01*
X189000Y172750D02*
G03X186500Y175250I-2500J0D01*
G54D31*
G01X381000Y142000D03*
G54D42*
X391000D02*
Y142485D01*
X391485*
X385087Y148882*
Y161979*
X222186Y172285D02*
X331129D01*
X385087Y170000D02*
X387087Y172000D01*
X549245*
X549530Y172285*
X549530*
X446753*
X385087Y170000D02*
X382802Y172285D01*
X331129*
X385087Y161979D02*
Y170000D01*
X446753Y172285D02*
X446753D01*
X446753*
X433392D02*
X446753D01*
X549530*
G54D43*
X194600Y145063D03*
X358400D03*
X140000D03*
X467600D03*
X522200D03*
X303800D03*
X249200D03*
X576800D03*
X631400D03*
X413000D03*
G54D44*
X194600Y154937D03*
X358400D03*
X140000D03*
X467600D03*
X522200D03*
X303800D03*
X249200D03*
X576800D03*
X631400D03*
X413000D03*
G54D45*
X395087Y161979D03*
X385087D03*
X375087D03*
G54D46*
X222186Y137285D03*
Y172285D03*
X446753Y137285D03*
Y172285D03*
X331129Y137285D03*
Y172285D03*
X549530Y137285D03*
Y172285D03*
X433392Y137285D03*
Y172285D03*
G54D47*
X140000Y154937D02*
X174073D01*
X194600Y145063D02*
X183947D01*
X174073Y154937*
X194600D02*
X204534D01*
X222186Y137285*
X303800Y145063D02*
X294547D01*
X284673Y154937*
X249200D02*
X284673D01*
X303800D02*
X313477D01*
X378747Y134000D02*
X401937D01*
X413000Y145063*
X378747Y134000D02*
X370000Y142747D01*
Y145453*
X359458Y155995*
X358400Y154937*
X331129Y137285D02*
X313477Y154937D01*
X423742Y146935D02*
X423119D01*
X414058Y155995*
X467600Y154937D02*
X466542Y155995D01*
X467600Y145063D02*
X478153D01*
X488027Y154937*
X522200*
X433392Y137285D02*
X423742Y146935D01*
X446753Y137285D02*
X455468Y146000D01*
X456547*
X466542Y155995*
X413000Y154937D02*
X414058Y155995D01*
X549530Y137285D02*
X567182Y154937D01*
X576800*
Y145063D02*
X587753D01*
X597627Y154937*
X631400*
G54D48*
X626332Y150131D02*
X629067Y147396D01*
X636468Y150131D02*
X633733Y147396D01*
X636468Y139995D02*
X633733Y142730D01*
X626332Y139995D02*
X629067Y142730D01*
X244132Y150131D02*
X246867Y147396D01*
X254268Y150131D02*
X251533Y147396D01*
X254268Y139995D02*
X251533Y142730D01*
X244132Y139995D02*
X246867Y142730D01*
X517132Y150131D02*
X519867Y147396D01*
X527268Y150131D02*
X524533Y147396D01*
X527268Y139995D02*
X524533Y142730D01*
X517132Y139995D02*
X519867Y142730D01*
X134932Y150131D02*
X137667Y147396D01*
X145068Y150131D02*
X142333Y147396D01*
X145068Y139995D02*
X142333Y142730D01*
X134932Y139995D02*
X137667Y142730D01*
X353332Y150131D02*
X356067Y147396D01*
X363468Y139995D02*
X360733Y142730D01*
X353332Y139995D02*
X356067Y142730D01*
X370069Y156961D02*
X372789Y159681D01*
X370069Y166997D02*
X372789Y164277D01*
X380105Y156961D02*
X377385Y159681D01*
X390069Y156961D02*
X392789Y159681D01*
X400105Y166997D02*
X397385Y164277D01*
X400105Y156961D02*
X397385Y159681D01*
G74*
X0Y0D02*
M02*
/roboti/istrobot/camerus/HW/CAM_PROFI/V2.rep
0,0 → 1,22
 
 
Photo-Plotter Apertures Report
==============================
Position Width Hgt/ID Shape Qty
======== ===== ====== ===== ===
12 70 0 SQR 1
13 236.22 0 RND 4
25 10 0 RND 306
31 70 0 RND 1
42 45 0 RND 17
43 66 0 SQR 10
44 66 0 RND 10
45 65 0 SQR 3
46 82.68 0 RND 10
47 35 0 RND 32
48 25 0 RND 25
 
 
 
 
 
/roboti/istrobot/camerus/HW/PCB/LEDpanel.pcb
Cannot display: file marked as a binary type.
svn:mime-type = application/octet-stream
Property changes:
Added: svn:mime-type
+application/octet-stream
\ No newline at end of property
/roboti/istrobot/camerus/HW/SCH/LEDPANEL.DSN
Cannot display: file marked as a binary type.
svn:mime-type = application/octet-stream
Property changes:
Added: svn:mime-type
+application/octet-stream
\ No newline at end of property
/roboti/istrobot/camerus/HW/SCH/LEDPANEL.ONL
0,0 → 1,274
(PCB LEDPANEL
(description
(timeStamp "2007 03 11 21 45 48")
(program "CAPTURE.EXE" (Version "10.5.0.p001 CIS - D"))
(source "Original data from OrCAD/CAPTURE schematic")
(title "LEDpanel")
(date "Sunday, March 11, 2007")
(document "D:\\KAKLIK\\PROJEKTY\\ROBOTI\\ISTROBOT\\CAMERUS\\HW\\SCH\\LEDPANEL.DSN")
(revision "")
(organization "")
(address1 "")
(address2 "")
(address3 "")
(address4 "")
(partvaluecombine "{Value}")
(pcbfootprintcombine "{Device},{Value}@{PCB Footprint}"))
(structure )
(placement
(component JUMP3
(place J1
(property
("PCB Footprint" JUMP3)
(Device JUMP3)
(timestamp 000003DB)
("Source Package" JUMP3)
(Value JUMP3))))
(component RL090
(place R1
(property
("PCB Footprint" RL090)
(Device R)
(timestamp 000000CF)
("Source Package" RL090)
(Value RL090)))
(place R2
(property
("PCB Footprint" RL090)
(Device R)
(timestamp 000000DF)
("Source Package" RL090)
(Value RL090)))
(place R3
(property
("PCB Footprint" RL090)
(Device R)
(timestamp 000000EF)
("Source Package" RL090)
(Value RL090)))
(place R4
(property
("PCB Footprint" RL090)
(Device R)
(timestamp 000000FF)
("Source Package" RL090)
(Value RL090)))
(place R5
(property
("PCB Footprint" RL090)
(Device R)
(timestamp 0000010F)
("Source Package" RL090)
(Value RL090))))
(component LED5mm
(place D10
(property
("PCB Footprint" LED5)
(Device LED)
(timestamp 000000B6)
("Source Package" LED5mm)
(Value LED5mm)))
(place D1
(property
("PCB Footprint" LED5)
(Device LED)
(timestamp 00000026)
("Source Package" LED5mm)
(Value LED5mm)))
(place D2
(property
("PCB Footprint" LED5)
(Device LED)
(timestamp 00000036)
("Source Package" LED5mm)
(Value LED5mm)))
(place D3
(property
("PCB Footprint" LED5)
(Device LED)
(timestamp 00000046)
("Source Package" LED5mm)
(Value LED5mm)))
(place D4
(property
("PCB Footprint" LED5)
(Device LED)
(timestamp 00000056)
("Source Package" LED5mm)
(Value LED5mm)))
(place D5
(property
("PCB Footprint" LED5)
(Device LED)
(timestamp 00000066)
("Source Package" LED5mm)
(Value LED5mm)))
(place D6
(property
("PCB Footprint" LED5)
(Device LED)
(timestamp 00000076)
("Source Package" LED5mm)
(Value LED5mm)))
(place D7
(property
("PCB Footprint" LED5)
(Device LED)
(timestamp 00000086)
("Source Package" LED5mm)
(Value LED5mm)))
(place D8
(property
("PCB Footprint" LED5)
(Device LED)
(timestamp 00000096)
("Source Package" LED5mm)
(Value LED5mm)))
(place D9
(property
("PCB Footprint" LED5)
(Device LED)
(timestamp 000000A6)
("Source Package" LED5mm)
(Value LED5mm))))
(component "C-ELYT-CE025X6"
(place C1
(property
("PCB Footprint" CE025X6)
(Device "C-ELYT")
(timestamp 000003AA)
("Source Package" "C-ELYT-CE025X6")
(Value 1000uF))))
(component HOLE_M3
(place M1
(property
("PCB Footprint" HOLE_M3)
(Device PAD)
(timestamp 00000619)
("Source Package" HOLE_M3)
(Value HOLE_M3)))
(place M2
(property
("PCB Footprint" HOLE_M3)
(Device PAD)
(timestamp 00000643)
("Source Package" HOLE_M3)
(Value HOLE_M3)))
(place M3
(property
("PCB Footprint" HOLE_M3)
(Device PAD)
(timestamp 0000066D)
("Source Package" HOLE_M3)
(Value HOLE_M3)))
(place M4
(property
("PCB Footprint" HOLE_M3)
(Device PAD)
(timestamp 00000697)
("Source Package" HOLE_M3)
(Value HOLE_M3)))))
(library
(image RL090
(property
(sourcelib C:\\LIBRARY\\ORCAD9X\\COM_RLC.OLB)
(Device R))
(pin 999 1
(property
(pinname 1)
(pintype 4)))
(pin 999 2
(property
(pinname 2)
(pintype 4))))
(image "C-ELYT-CE025X6"
(property
(sourcelib C:\\LIBRARY\\ORCAD9X\\COM_RLC.OLB)
(Device "C-ELYT"))
(pin 999 A
(property
(pinname A)
(pintype 4)))
(pin 999 C
(property
(pinname C)
(pintype 4))))
(image HOLE_M3
(property
(sourcelib C:\\LIBRARY\\ORCAD9X\\PAD.OLB)
(Device PAD))
(pin 999 1
(property
(pinname PIN)
(pintype 4))))
(image JUMP3
(property
(sourcelib C:\\LIBRARY\\ORCAD9X\\JUMP.OLB)
(Device JUMP3))
(pin 999 1
(property
(pinname 1)
(pintype 4)))
(pin 999 2
(property
(pinname 2)
(pintype 4)))
(pin 999 3
(property
(pinname 3)
(pintype 4))))
(image LED5mm
(property
(sourcelib C:\\LIBRARY\\ORCAD9X\\COM_OPTO.OLB)
(Device LED))
(pin 999 A
(property
(pinname A)
(pintype 4)))
(pin 999 C
(property
(pinname C)
(pintype 4)))))
(network
(net VCC
(property
(nettype S))
(pins
R3-2 C1-A J1-2 R5-2 R1-2 R2-2 R4-2))
(net GND
(property
(nettype S))
(pins
D8-C C1-C D4-C M1-1 D2-C M3-1 M4-1 D6-C J1-3
J1-1 M2-1 D10-C))
(net N00380
(pins
R1-1 D1-A))
(net N00388
(pins
D1-C D2-A))
(net N00433
(pins
D4-A D3-C))
(net N00446
(pins
D3-A R2-1))
(net N00494
(pins
R3-1 D5-A))
(net N00649
(pins
D5-C D6-A))
(net N00715
(pins
D7-A R4-1))
(net N00793
(pins
R5-1 D9-A))
(net N00822
(pins
D9-C D10-A))
(net N00885
(pins
D7-C D8-A)))
)
/roboti/istrobot/camerus/HW/SCH/LEDPANEL.asc
0,0 → 1,51
*PADS-PCB*
*PART*
C1 C-ELYT,1000uF@CE025X6
D1 LED,LED5mm@LED5
D10 LED,LED5mm@LED5
D2 LED,LED5mm@LED5
D3 LED,LED5mm@LED5
D4 LED,LED5mm@LED5
D5 LED,LED5mm@LED5
D6 LED,LED5mm@LED5
D7 LED,LED5mm@LED5
D8 LED,LED5mm@LED5
D9 LED,LED5mm@LED5
J1 JUMP3,JUMP3@JUMP3
M1 PAD,HOLE_M3@HOLE_M3
M2 PAD,HOLE_M3@HOLE_M3
M3 PAD,HOLE_M3@HOLE_M3
M4 PAD,HOLE_M3@HOLE_M3
R1 R,RL090@RL090
R2 R,RL090@RL090
R3 R,RL090@RL090
R4 R,RL090@RL090
R5 R,RL090@RL090
 
*NET*
*SIGNAL* VCC
R3.2 C1.A J1.2 R5.2 R1.2 R2.2 R4.2
*SIGNAL* GND
D8.C C1.C D4.C M1.1 D2.C M3.1 M4.1 D6.C
J1.3 J1.1 M2.1 D10.C
*SIGNAL* N00380
R1.1 D1.A
*SIGNAL* N00388
D1.C D2.A
*SIGNAL* N00433
D4.A D3.C
*SIGNAL* N00446
D3.A R2.1
*SIGNAL* N00494
R3.1 D5.A
*SIGNAL* N00649
D5.C D6.A
*SIGNAL* N00715
D7.A R4.1
*SIGNAL* N00793
R5.1 D9.A
*SIGNAL* N00822
D9.C D10.A
*SIGNAL* N00885
D7.C D8.A
*END*
/roboti/istrobot/camerus/HW/SCH/LEDPANEL_0.DBK
Cannot display: file marked as a binary type.
svn:mime-type = application/octet-stream
Property changes:
Added: svn:mime-type
+application/octet-stream
\ No newline at end of property
/roboti/istrobot/camerus
Property changes:
Added: svn:ignore
+*.bak
+*.BAK
+*.cof
+*.err
+*.hex
+*.lst
+*.sta
+*.sym
+*.tre
/roboti/istrobot/cholerik/cholerik.PJT
0,0 → 1,43
[PROJECT]
Target=tank.HEX
Development_Mode=
Processor=0x688F
ToolSuite=CCS
 
[Directories]
Include=C:\Program Files\PICC\devices\;C:\Program Files\PICC\drivers\;C:\library\CCS;
Library=
LinkerScript=
 
[Target Data]
FileList=D:\KAKLIK\projekty\roboti\istrobot\cholerik\cholerik.c
BuildTool=C-COMPILER
OptionString=+FM
AdditionalOptionString=
BuildRequired=1
 
[tank.c]
Type=4
Path=
FileList=
BuildTool=
OptionString=
AdditionalOptionString=
 
[mru-list]
1=tank.c
 
[Windows]
0=0000 tank.c 0 0 796 451 3 0
 
[Opened Files]
1=D:\KAKLIK\projekty\roboti\istrobot\cholerik\cholerik.c
2=
3=C:\Program Files\PICC\devices\16F88.h
4=
5=
6=
7=
[Units]
Count=1
1=D:\KAKLIK\projekty\roboti\istrobot\cholerik\cholerik.c (main)
/roboti/istrobot/cholerik/cholerik.c
0,0 → 1,274
// Program pro MiniSumo na R-Day 2006
//"$Id$"
 
#include "cholerik.h"
 
#define THRESHOLD 15 // rozhodovaci uroven pro okraj areny
// 0-15 (od 0.25 do 0.75 Vdd)
// 0 jasnejsi; 15 tmavsi
 
//motory //Napred vypnout potom zapnout!
#define FR output_low(PIN_B5); output_high(PIN_B4) // Vpred
#define FL output_low(PIN_B7); output_high(PIN_B6)
#define BR output_low(PIN_B4); output_high(PIN_B5) // Vzad
#define BL output_low(PIN_B6); output_high(PIN_B7)
#define STOPR output_low(PIN_B4);output_low(PIN_B5) // Zastav
#define STOPL output_low(PIN_B6);output_low(PIN_B7)
 
//cidla
#define SIDE_R !input(PIN_A7) // Sensory na soupere
#define SIDE_L !input(PIN_A4)
#define FRONT !input(PIN_A6)
#define BACK !input(PIN_B3)
#define GRAVITY !input(PIN_A1)
// PIN_A3 Prave cidlo na okraj areny (C1OUT)
// PIN_A2 Leve cidlo na okraj areny (C2OUT)
 
#DEFINE SOUND_HI PIN_B1 // komplementarni vystupy pro piezo pipak
#DEFINE SOUND_LO PIN_B2
 
// makro pro PWM
#define GO(motor, direction, power) if(get_timer0()<=power) \
{direction##motor;} else {stop##motor;}
 
unsigned int8 majak=0;
unsigned int8 sl=0;
unsigned int8 sr=0;
unsigned int8 b=0;
unsigned int8 f=0;
unsigned int8 g=0;
int1 arena_l=FALSE;
int1 arena_r=FALSE;
int1 diag=FALSE;
 
#int_TIMER0
TIMER0_isr()
{
int1 stav;
 
stav = ((majak & 0b1) == 0b1);
if (((SIDE_R && stav) || (!SIDE_R && !stav))) {if (sr<255) sr++;} else {sr=0;};
if (((SIDE_L && stav) || (!SIDE_L && !stav))) {if (sl<255) sl++;} else {sl=0;};
if (((BACK && stav) || (!BACK && !stav))) {if (b<255) b++;} else {b=0;};
if (((FRONT && stav) || (!FRONT && !stav))) {if (f<255) f++;} else {f=0;};
majak++;
stav = ((majak & 0b1) == 0b1);
 
if (!C1OUT) arena_r=TRUE; else arena_r=FALSE;
if (!C2OUT) arena_l=TRUE; else arena_l=FALSE;
 
if (stav)
{
set_pwm1_duty(27); // 1:1
}
else
{
set_pwm1_duty(55); // 1:0
};
setup_comparator(NC_NC_NC_NC); // inicializace komparatoru
if (GRAVITY) {if (g<255) g++;} else g=0;
setup_comparator(A3_VR_A2_VR); // inicializace komparatoru
if (g>3 && !diag) {FL; FR; while(TRUE);}; // kdyz nas preklopi, nedej se
}
 
// Primitivni Pipani
void beep(unsigned int16 period, unsigned int16 length)
{
unsigned int16 nn;
 
disable_interrupts(GLOBAL);
for(nn=length; nn>0; nn--)
{
output_high(SOUND_HI);output_low(SOUND_LO);
delay_us(period);
output_high(SOUND_LO);output_low(SOUND_HI);
delay_us(period);
}
enable_interrupts(GLOBAL);
}
 
/**** DIAG ********************************************************************/
inline void diagnostika()
{
unsigned int16 n;
 
setup_comparator(NC_NC_NC_NC); // inicializace komparatoru
if (GRAVITY)
{
setup_comparator(A3_VR_A2_VR); // inicializace komparatoru
diag=TRUE;
enable_interrupts(INT_TIMER0);
enable_interrupts(GLOBAL);
while (true) // Diagnostika cidel
{
if (g>100) beep(800,100);
Delay_ms(50);
if (arena_l) {beep(1000,200); delay_ms(10);beep(1000,200);};
Delay_ms(50);
if (arena_r) {beep(2000,300); delay_ms(10);beep(2000,300);};
Delay_ms(50);
 
if (sr>10) beep(3000,400);
Delay_ms(50);
if (f>10) beep(4000,500);
Delay_ms(50);
if (sl>10) beep(5000,500);
Delay_ms(50);
if (b>10) beep(6000,600);
Delay_ms(50);
if((g>100) && arena_l && arena_r) break; // Preklopen na zada a bily papir na obou cidlech na okraj areny
};
 
while(TRUE) // Diagnostika podvozku
{
for (n=500; n<800; n+=100)
{
beep(n,n); //beep UP
};
Delay_ms(1000);
//zastav vse
STOPL; STOPR;
//pravy pas
FR; Delay_ms(1000); STOPR; Delay_ms(1000);
BR; Delay_ms(1000); STOPR; Delay_ms(1000);
Beep(880,100); Delay_ms(1000);
//levy pas
FL; Delay_ms(1000); STOPL; Delay_ms(1000);
BL; Delay_ms(1000); STOPL; Delay_ms(1000);
Beep(880,100); Delay_ms(1000);
//oba pasy
FL; FR; Delay_ms(1000); STOPL; STOPR; Delay_ms(1000);
BL; BR; Delay_ms(1000); STOPL; STOPR; Delay_ms(1000);
};
};
}
 
/**** MAIN ********************************************************************/
void main()
{
unsigned int16 n; // for FOR
 
STOPL; STOPR; // zastavi motory
 
setup_oscillator(OSC_8MHZ|OSC_INTRC); // CPU clock 8MHz
setup_adc_ports(NO_ANALOGS); // komparatory vypnuty
setup_adc(ADC_OFF);
setup_spi(FALSE);
setup_timer_0(RTCC_INTERNAL|RTCC_DIV_4); // Casovac pro SW PWM a cteni cidel
setup_timer_1(T1_DISABLED);
setup_timer_2(T2_DIV_BY_1,54,1); // Casovac pro PWM pro IR sensory cca 36kHz
setup_ccp1(CCP_PWM); // HW PWM ON
set_pwm1_duty(27); // 1:1
setup_comparator(A3_VR_A2_VR); // inicializace komparatoru
setup_comparator(NC_NC_NC_NC); // inicializace komparatoru
setup_vref(VREF_HIGH|THRESHOLD); // 16 kroku od 0.25 do 0.75 Vdd
 
Beep(1000,200); //double beep
Delay_ms(50);
Beep(1000,200);
diagnostika();
 
enable_interrupts(INT_TIMER0);
enable_interrupts(GLOBAL);
 
for (n=1;n<=5;n++) // 5s do zacatku souboje
{
Delay_ms(670); // 5,25s
Beep(1000,200);
}
 
/*----- Main Loop ------------------------------------------------------------*/
while(true) // hlavni smycka
{
LOOP:
 
GO(L, F, 150); GO(R, F, 150);
 
if (arena_r)
{
BL; BR;
delay_ms(180);
STOPL; BR;
for(n=0; n<5000; n++)
{
if (!arena_r || arena_l) {BL; BR;};
};
FL; BR;
delay_ms(100);
STOPL; STOPR;
}
 
if (arena_l)
{
BL; BR;
delay_ms(180);
BL; STOPR;
for(n=0; n<5000; n++)
{
if (!arena_l || arena_r) {BL; BR;};
};
BL; FR;
delay_ms(100);
STOPL; STOPR;
}
 
if (sr>10) // Nepritel vpravo
{
FL; FR; // popojed rovne
for(n=0; n<5000; n++)
{
if (arena_l || arena_r) {BL; BR; delay_ms(100); goto LOOP;};
};
FL; BR; // otoc se na nej
for(n=0; n<10000; n++)
{
if (arena_l || arena_r) {BL; BR; delay_ms(100); goto LOOP;};
if (f>5)
{
FL; FR; // vytlac ho
};
if (sl>5) {BL; FR;};
if (sr>5) {FL; BR;};
};
}
 
if (sl>10) // Nepritel vlevo
{
FL; FR; // popojed rovne
for(n=0; n<5000; n++)
{
if (arena_l || arena_r) {BL; BR; delay_ms(100); goto LOOP;};
};
BL; FR; // otoc se na nej
for(n=0; n<10000; n++)
{
if (arena_l || arena_r) {BL; BR; delay_ms(100); goto LOOP;};
if (f>5)
{
FL; FR; // vytlac ho
};
if (sl>5) {BL; FR;};
if (sr>5) {FL; BR;};
};
}
 
if (f>10) // Nepritel vpredu
{
BL; FR;
delay_ms(110);
FL; BR;
delay_ms(50);
STOPL; STOPR;
}
 
if (b>10) // Nepritel vzadu
{
BL; FR;
delay_ms(110);
FL; BR;
delay_ms(50);
STOPL; STOPR;
}
 
} // while(true)
}
Property changes:
Added: svn:keywords
+Id Rev
\ No newline at end of property
/roboti/istrobot/cholerik/cholerik.h
0,0 → 1,19
#include <16F88.h>
#device adc=8
 
#FUSES NOWDT //No Watch Dog Timer
#FUSES INTRC_IO //Internal RC Osc, no CLKOUT
#FUSES NOPUT //No Power Up Timer
#FUSES MCLR //Master Clear pin enabled
#FUSES NOBROWNOUT //No brownout reset
#FUSES NOLVP //No low voltage prgming, B3(PIC16) or B5(PIC18) used for I/O
#FUSES NOCPD //No EE protection
#FUSES NOWRT //Program memory not write protected
#FUSES NODEBUG //No Debug mode for ICD
#FUSES NOPROTECT //Code not protected from reading
#FUSES NOFCMEN //Fail-safe clock monitor disabled
#FUSES NOIESO //Internal External Switch Over mode disabled
#FUSES CCPB0 //Vystup PWM
 
#use delay(clock=8000000)
 
/roboti/istrobot/merkur/PIC16F88/README.txt
0,0 → 1,6
Složka MerkurU obsahuje zdrojáky pro jízdu po neuzavřené křivce
 
Složka turn_L obsahuje zdroják pro objíždění cihly vlevo
Složka turn_R obsahuje zdroják pro objíždění cihly vpravo
 
A složka vystava je verze firmware pro výstavně ježdění, zařazena rutina pro usporný režim a šetření motorů.
/roboti/istrobot/merkur/PIC16F88/MerkurU/AX25.c
0,0 → 1,135
#nolist
//#define PTT PIN_A2 // PTT control
//#define TXo PIN_C0 // To the transmitter modulator
#define PERIODAH delay_us(222) // Halfperiod H 222;78/1200 500;430/500
#define TAILH delay_us(78)
#define PERIODAL delay_us(412) // Halfperiod L 412;345/1200 1000;880/500
#define TAILL delay_us(345)
#byte STATUS = 3 // CPUs status register
 
byte SendData[16] = {'A'<<1, 'L'<<1, 'L'<<1, ' '<<1, ' '<<1, ' '<<1, 0x60,
'C'<<1, 'Z'<<1, '0'<<1, 'R'<<1, 'R'<<1, 'R'<<1, 0x61,
0x03, 0xF0};
 
boolean bit;
int fcslo, fcshi; // variabloes for calculating FCS (CRC)
int stuff; // stuff counter for extra 0
int flag_flag; // if it is sending flag (7E)
int fcs_flag; // if it is sending Frame Check Sequence
int i; // for for
 
void flipout() //flips the state of output pin a_1
{
stuff = 0; //since this is a 0, reset the stuff counter
if (bit)
{
bit=FALSE; //if the state of the pin was low, make it high.
}
else
{
bit=TRUE; //if the state of the pin was high make it low
}
}
 
void fcsbit(byte tbyte)
{
#asm
BCF STATUS,0
RRF fcshi,F // rotates the entire 16 bits
RRF fcslo,F // to the right
#endasm
if (((STATUS & 0x01)^(tbyte)) ==0x01)
{
fcshi = fcshi^0x84;
fcslo = fcslo^0x08;
}
}
 
void SendBit ()
{
if (bit)
{
output_high(TXo);
PERIODAH;
output_low(TXo);
PERIODAH;
output_high(TXo);
PERIODAH;
output_low(TXo);
TAILH;
}
else
{
output_high(TXo);
PERIODAL;
output_low(TXo);
TAILL;
};
}
 
void SendByte (byte inbyte)
{
int k, bt;
 
for (k=0;k<8;k++) //do the following for each of the 8 bits in the byte
{
bt = inbyte & 0x01; //strip off the rightmost bit of the byte to be sent (inbyte)
if ((fcs_flag == FALSE) & (flag_flag == FALSE)) fcsbit(bt); //do FCS calc, but only if this
//is not a flag or fcs byte
if (bt == 0)
{
flipout();
} // if this bit is a zero, flip the output state
else
{ //otherwise if it is a 1, do the following:
if (flag_flag == FALSE) stuff++; //increment the count of consequtive 1's
if ((flag_flag == FALSE) & (stuff == 5))
{ //stuff an extra 0, if 5 1's in a row
SendBit();
flipout(); //flip the output state to stuff a 0
}//end of if
}//end of else
// delay_us(850); //introduces a delay that creates 1200 baud
SendBit();
inbyte = inbyte>>1; //go to the next bit in the byte
}//end of for
}//end of SendByte
 
void SendPacket(char *data)
{
bit=FALSE;
 
fcslo=fcshi=0xFF; //The 2 FCS Bytes are initialized to FF
stuff = 0; //The variable stuff counts the number of 1's in a row. When it gets to 5
// it is time to stuff a 0.
 
// output_low(PTT); // Blinking LED
// delay_ms(1000);
// output_high(PTT);
 
flag_flag = TRUE; //The variable flag is true if you are transmitted flags (7E's) false otherwise.
fcs_flag = FALSE; //The variable fcsflag is true if you are transmitting FCS bytes, false otherwise.
 
for(i=0; i<10; i++) SendByte(0x7E); //Sends flag bytes. Adjust length for txdelay
//each flag takes approx 6.7 ms
flag_flag = FALSE; //done sending flags
 
for(i=0; i<16; i++) SendByte(SendData[i]); //send the packet bytes
 
for(i=0; 0 != *data; i++)
{
SendByte(*data); //send the packet bytes
data++;
};
 
fcs_flag = TRUE; //about to send the FCS bytes
fcslo =fcslo^0xff; //must XOR them with FF before sending
fcshi = fcshi^0xff;
SendByte(fcslo); //send the low byte of fcs
SendByte(fcshi); //send the high byte of fcs
fcs_flag = FALSE; //done sending FCS
flag_flag = TRUE; //about to send flags
SendByte(0x7e); // Send a flag to end packet
}
 
#list
/roboti/istrobot/merkur/PIC16F88/MerkurU/tank.BAK
0,0 → 1,268
// Program pro predvadeni schopnosti robota Merkur
//------------------------------------------------
 
#include "tank.h"
 
unsigned int8 sensors; // pomocna promenna pro cteni cidel na caru
unsigned int8 line; // na ktere strane byla detekovana cara
unsigned int8 speed; // rychlost zataceni
unsigned int8 last; // kde byla cara, kdyz byly minule cidla mimo
unsigned int8 rovinka; // pocitadlo pro zjisteni rovneho useku
int cirkus; // pocitadlo, po kolika akcich se ma delat cirkus
int1 BW; // urcuje, jestli je cara cerno/bila nebo
// bilo/cerna (true = bila cara, cerny podklad)
 
// Konstanty pro dynamiku pohybu
#define T_DIRA 120 // po jakem case zataceni se detekuje dira
#define FW_POMALU 170 // trochu mimo caru vnitrni pas
#define FW_ZATACKA 200 // rychlost vnejsiho kola pri zataceni
#define FW_STREDNE 190 // trochu mimo caru vnejsi pas
#define COUVANI 750 // couvnuti zpet na caru, po detekci diry
#define MAX_ROVINKA (255-FW_STREDNE)
#define TRESHOLD 15 // rozhodovaci uroven komparatoru, 0xF = 0.75*Vdd
#define BUMPER_TRESHOLD 128 // rozhodovaci uroven cidla na prekazku
 
//motory //Napred vypnout potom zapnout!
#define FR output_low(PIN_B5); output_high(PIN_B4) // Vpred
#define FL output_low(PIN_B7); output_high(PIN_B6)
#define BR output_low(PIN_B4); output_high(PIN_B5) // Vzad
#define BL output_low(PIN_B6); output_high(PIN_B7)
#define STOPR output_low(PIN_B4);output_low(PIN_B5) // Zastav
#define STOPL output_low(PIN_B6);output_low(PIN_B7)
 
#define L 0b10 // left
#define R 0b01 // right
#define S 0b11 // straight
 
//cidla
#define RSENSOR (BW != C2OUT) // Senzory na caru
#define LSENSOR (BW != C1OUT)
#define BUMPER sAN2 // Senzor na cihlu
 
#define DIAG_SERVO PIN_B3 // Propojka pro diagnosticky mod
#define DIAG_SENSORS PIN_B2 // Propojka pro diagnosticky mod
#define BARVY PIN_B1 // Propojka pro nastaveni barvy cary
 
#define SPEAKER PIN_B0 // vystup pro pipak
 
#define LED1 PIN_A4 // LEDky
#define LED2 PIN_A3
#define LED3 PIN_A7
#define LED4 PIN_A6
 
// makro pro PWM
#define GO(motor, direction, power) if(get_timer0()<=power) \
{direction##motor;} else {stop##motor;}
 
#int_TIMER2
void TIMER2_isr() // obsluha zrychlovani
{
if (speed<255) speed++;
if (rovinka<MAX_ROVINKA) rovinka++;
}
 
// Primitivni Pipani
void beep(unsigned int16 period, unsigned int16 length)
{
unsigned int16 nn;
 
for(nn=length; nn>0; nn--)
{
output_high(SPEAKER);
delay_us(period);
output_low(SPEAKER);
delay_us(period);
}
}
/******************************************************************************/
void diagnostika()
{
unsigned int16 n;
 
while (input(DIAG_SERVO)) // Propojka, ktera spousti diagnostiku
{
for (n=500; n<800; n+=100)
{
beep(n,n); //beep UP
};
Delay_ms(1000);
//zastav vse
STOPL; STOPR;
//pravy pas
FR; Delay_ms(1000); STOPR; Delay_ms(1000);
BR; Delay_ms(1000); STOPR; Delay_ms(1000);
Beep(880,100); Delay_ms(1000);
//levy pas
FL; Delay_ms(1000); STOPL; Delay_ms(1000);
BL; Delay_ms(1000); STOPL; Delay_ms(1000);
Beep(880,100); Delay_ms(1000);
//oba pasy
FL; FR; Delay_ms(1000); STOPL; STOPR; Delay_ms(1000);
BL; BR; Delay_ms(1000); STOPL; STOPR; Delay_ms(1000);
};
while (input(DIAG_SENSORS)) // spusteni diagnostiky cidel
{
if (RSENSOR) beep(1000,200);
Delay_ms(300);
if (LSENSOR) beep(2000,300);
Delay_ms(300);
if ((read_adc(ADC_READ_ONLY)<BUMPER_TRESHOLD)) beep(3000,400);
Delay_ms(300);
};
}
///////////////////////////////////////////////////////////////////////////////
void OtocSe() // otoci se zpet, kdyz je prekazka
{
unsigned int16 n;
 
BL; BR; // cukni zpatky
Delay_ms(200);
STOPR;STOPL;
beep(800,400);
beep(2000,1000);
output_low(LED4);
beep(900,400);
output_low(LED1);
 
BR; FL; Delay_ms(100); // otoc se 30° do prava
STOPL; STOPR;
beep(1000,1000);
output_low(LED3);
 
BR; FL;
for(n=40000;n>0;n--) // toc se, dokud nenarazis na caru
{
line = RSENSOR; // cteni senzoru na caru
line |= LSENSOR << 1;
if (line!=0) break;
}
STOPR; STOPL;
output_high(LED1); output_high(LED3); output_high(LED4);
 
line=L; // caru jsme prejeli, tak je vlevo
cirkus=0;
}
 
 
void main()
{
unsigned int16 n; // pro FOR
unsigned int16 i;
 
STOPL; STOPR; // prepne vystupy na ovladani motoru na output a zastavi
 
setup_oscillator(OSC_4MHZ|OSC_INTRC); // 4 MHz interni RC oscilator
 
port_b_pullups(TRUE); // pullups pro piano na diagnostiku
setup_spi(FALSE);
setup_timer_0(RTCC_INTERNAL|RTCC_DIV_1); // Casovac pro PWM
 
setup_timer_2(T2_DIV_BY_4,255,10); // Casovac pro regulaci
// preruseni kazdych 10ms
setup_adc_ports(BUMPER|VSS_VDD); // nastaveni A/D prevodniku pro naraznik
setup_adc(ADC_CLOCK_INTERNAL);
set_adc_channel(2);
setup_timer_1(T1_INTERNAL|T1_DIV_BY_1); // Casovac pro naraznik
setup_ccp1(CCP_COMPARE_RESET_TIMER);
CCP_1=(2^10)-1; // prevod kazdou 1ms
 
output_low(LED1); output_low(LED2); output_low(LED3); output_low(LED4);
 
setup_comparator(A0_VR_A1_VR); // inicializace komparatoru pro cidla cary
setup_vref(VREF_HIGH|TRESHOLD); // 32 kroku od 0.25 do 0.75 Vdd
 
Beep(1000,200); //double beep
Delay_ms(50);
Beep(1000,200);
Delay_ms(1000); // 1s
 
// povoleni rizeni rychlosti zataceni pres preruseni
enable_interrupts(INT_TIMER2);
enable_interrupts(GLOBAL);
 
/*---------------------------------------------------------------------------*/
sensors=S;
line=S;
last=S;
cirkus=0;
// movement=S;
speed=FW_POMALU;
 
BW=input(BARVY); // Jaka ma byt barva cary?
diagnostika(); // Zkus, jestli nekdo nechce, diagnostiku
Delay_ms(500);
 
output_high(LED1); Beep(1000,200); Delay_ms(500);
output_high(LED2); Beep(1000,200); Delay_ms(500);
output_high(LED3); Beep(1000,200); Delay_ms(500);
output_high(LED4); Beep(1000,200); Delay_ms(500);
 
while(true) // hlavni smycka (jizda podle cary)
{
sensors = RSENSOR; // cteni senzoru na caru
sensors |= LSENSOR << 1;
 
if (read_adc(ADC_READ_ONLY)<BUMPER_TRESHOLD) OtocSe();
 
switch (sensors) // zatacej podle toho, kde vidis caru
{
case S: // rovne
GO(L, F, FW_STREDNE+rovinka); GO(R, F, FW_STREDNE+rovinka);
continue;
case L: // trochu vlevo
GO(L, F, FW_POMALU+rovinka); GO(R, F, FW_STREDNE+rovinka);
line=L;
continue;
case R: // trochu vpravo
GO(R, F, FW_POMALU+rovinka); GO(L, F, FW_STREDNE+rovinka);
line=R;
continue;
default: // kdyz jsou obe cidla mimo caru, tak pokracuj dal
};
rovinka=0;
 
if (last!=line) // pokud si prejel caru z jedne strany na druhou stranu,
// tak zabrzdi
{
output_bit(LED1, !input(LED1));
last=line;
speed=FW_ZATACKA;
cirkus++;
if (cirkus>8)
{
STOPL; STOPR;
cirkus=0;
disable_interrupts(GLOBAL);
beep(1000,400);
for(n=3000; n>3950; n--) beep(n,10);
output_low(LED1);
beep(2000,200);
beep(900,400);
for(n=2950; n<3000; n++) beep(n,10);
output_low(LED2);
output_high(LED1);
beep(4000,400);
beep(1000,100);
output_low(LED3);
beep(3000,400);
Delay_ms(1000);
output_high(LED1); output_high(LED2);
output_high(LED3); output_high(LED4);
enable_interrupts(GLOBAL);
}
};
 
if (L==line) // kdyz jsou obe cidla mimo caru, zatoc na caru
{
STOPL;
GO(R, F, speed);
}
else
{
STOPR;
GO(L, F, speed);
}
 
} // while(true)
}
 
/roboti/istrobot/merkur/PIC16F88/MerkurU/tank.HEX
0,0 → 1,184
:1000000000308A00D12A0000FF00030E8301A10006
:100010007F08A0000A08A8008A01A00E0408A20018
:100020007708A3007808A4007908A5007A08A6003C
:100030007B08A700831383128C308400801C222845
:100040008C183528220884002308F7002408F800BB
:100050002508F9002608FA002708FB0028088A006E
:10006000210E8300FF0E7F0E09008A1137282B0F07
:100070003A283B28AB0A2D08403C0318AD0A8C10E7
:100080008A1122281230BC02031C54283C30840000
:10009000FC3080050310800C800C000803195428E4
:1000A00052280000800B512800343908BB00380862
:1000B000BA00BA08031D5F28BB080319722883160B
:1000C0000610831206143608BC0042208316061060
:1000D000831206103608BC0042203A080319BB03FD
:1000E000BA035928003437308400000803198728E0
:1000F0000130F800F701F70B7B28F80B7A284A301B
:10010000F700F70B812800000000800B78280034EE
:10011000831686158312861DB3290130B500F4308D
:10012000B4003508033C031CA928031D9B28340890
:100130001F3C031CA9283508B7003408B600350851
:10014000B9003408B80055206430B4070318B50A64
:1001500091280430B600FA30B7007320B60BAB28F4
:1001600083160613831206138316861383128613CF
:1001700083160612831206128316861283128612C3
:1001800083168612831286128316061283120616AF
:100190000430B600FA30B7007320B60BCA288316B5
:1001A00006128312061283168612831286120430F8
:1001B000B600FA30B7007320B60BD92883160612A2
:1001C0008312061283168612831286160430B60036
:1001D000FA30B7007320B60BE82883160612831294
:1001E000061283168612831286120430B600FA3085
:1001F000B7007320B60BF7280330B7007030B60095
:10020000B9016430B80055200430B600FA30B700A8
:100210007320B60B06298316861383128613831662
:100220000613831206170430B600FA30B7007320A5
:10023000B60B15298316061383120613831686132D
:10024000831286130430B600FA30B7007320B60B61
:10025000242983160613831206138316861383122A
:1002600086170430B600FA30B7007320B60B332976
:1002700083160613831206138316861383128613BE
:100280000430B600FA30B7007320B60B42290330B1
:10029000B7007030B600B9016430B80055200430A2
:1002A000B600FA30B7007320B60B512983168613B7
:1002B000831286138316061383120617831686127B
:1002C0008312861283160612831206160430B600B5
:1002D000FA30B7007320B60B682983160613831211
:1002E000061383168613831286138316061283124F
:1002F000061283168612831286120430B600FA3074
:10030000B7007320B60B7F298316061383120613DA
:10031000831686138312861783160612831206121B
:1003200083168612831286160430B600FA30B700A0
:100330007320B60B962983160613831206138316B1
:1003400086138312861383160612831206128316EF
:100350008612831286120430B600FA30B70073207A
:10036000B60BAD298828831606158312061DF629BB
:10037000F70183169C1B771483122F087706013927
:100380000319CA290330B700E830B600B901C830F4
:10039000B8005520C830B7007320F70183161C1B26
:1003A000771483122F08770601390319E0290730E3
:1003B000B700D030B6000130B9002C30B80055205D
:1003C000C830B70073201F19E3291E087F3C031CA7
:1003D000F2290B30B700B830B6000130B9009030C8
:1003E000B8005520C830B7007320B3298A11782B84
:1003F0008316061383120613831686138312861739
:10040000831606128312061283168612831286162C
:10041000C830B700732083160612831206128316A3
:10042000861283128612831606138312061383160E
:100430008613831286130330B7002030B6000130D4
:10044000B9009030B80055200730B700D030B60062
:100450000330B900E830B800552083160513831225
:1004600005130330B7008430B6000130B900903076
:10047000B800552083160512831205128316061242
:10048000831206128316861283128616831686132B
:100490008312861383160613831206176430B7007F
:1004A0007320831606138312061383168613831292
:1004B000861383160612831206128316861283127F
:1004C00086120330B700E830B6000330B900E830D8
:1004D000B8005520831685138312851383160612E0
:1004E00083120612831686128312861683168613CB
:1004F0008312861383160613831206179C30B500E9
:100500004030B400B408031D882AB5080319B02A86
:10051000F70183169C1B771483122F087706013985
:10052000031D942A0030952A0130AA00F701831692
:100530001C1B771483122F0877060139031DA22A8A
:100540000030A32A0130F7000310F70D7708AA0442
:10055000AA08031DB02A34080319B503B403822A7C
:1005600083160612831206128316861283128612CF
:1005700083160613831206138316861383128613BB
:1005800083160512831205168316851383128517A9
:1005900083160513831205170230AA00AE018A11D3
:1005A000F12B84011F30830583161F129F121B0835
:1005B00080399B0007309C001C0883120D136030AB
:1005C00083168F0006138312061383168613831275
:1005D000861383160612831206128316861283125E
:1005E0008612623083168F00811383129412831651
:1005F00006118614061200308312940083169400AC
:100600000108C739083881004830F80005388312DE
:100610009200FF30831692001F129F121B08803930
:1006200004389B001F1383121F179F1783169F13F5
:1006300083121F141030F8001F08C73978049F0078
:1006400085309000831686150B3083129700960133
:100650000730950083160512831205128316851143
:100660008312851183168513831285138316051350
:1006700083120513023083169C0005080338850099
:100680000330F700F70B422B1C0883120D138F3039
:1006900083169D0003308312B700E830B600B9011D
:1006A000C830B80055203230B70073200330B7008F
:1006B000E830B600B901C830B80055200430B400A5
:1006C000FA30B7007320B40B602B83168C14C03043
:1006D00083128B040330A900AA00AC00AE01AA303B
:1006E000AB008316861483122F1086182F148828C7
:1006F0000230B400FA30B7007320B40B7A2B8316A3
:100700000512831205160330B700E830B600B901B0
:10071000C830B80055200230B400FA30B70073205A
:10072000B40B8D2B83168511831285150330B7000A
:10073000E830B600B901C830B80055200230B40026
:10074000FA30B7007320B40BA02B831685138312E5
:1007500085170330B700E830B600B901C830B800DB
:1007600055200230B400FA30B7007320B40BB32B1D
:1007700083160513831205170330B700E830B6005F
:10078000B901C830B80055200230B400FA30B700C3
:100790007320B40BC62BF70183169C1B77148312AE
:1007A0002F0877060139031DD72B0030D82B0130D5
:1007B000A900F70183161C1B771483122F087706F4
:1007C0000139031DE52B0030E62B0130F700031043
:1007D000F70D7708A9041F19EB2B1E087F3C03189F
:1007E000F8292908033A0319FC2B013A0319312C83
:1007F000033A0319682C9F2C0108B400BE302D0762
:1008000034020319052C03180E2C83168613831249
:1008100086138316061383120617162C83160613E7
:100820008312061383168613831286130108B400FD
:10083000BE302D07340203191F2C0318282C8316F1
:100840008612831286128316061283120616302C25
:1008500083160612831206128316861283128612DC
:10086000CB2B0108B400AA302D07340203193A2C0F
:100870000318432C831686138312861383160613DC
:10088000831206174B2C8316061383120613831646
:100890008613831286130108B400BE302D0734027C
:1008A0000319542C03185D2C8316861283128612AA
:1008B0008316061283120616652C831606128312FF
:1008C000061283168612831286120230AA00CB2BE0
:1008D0000108B400AA302D0734020319712C031843
:1008E0007A2C8316861283128612831606128312BE
:1008F0000616822C8316061283120612831686129F
:10090000831286120108B400BE302D073402031989
:100910008B2C0318942C831686138312861383164C
:100920000613831206179C2C8316061383120613D4
:1009300083168613831286130130AA00CB2BAD01D8
:100940002A082C020319602D831605168312051E32
:10095000AB2C0512AC2C05168316051283122A083F
:10096000AC00C830AB00AE0A2E08083C0318602D5E
:1009700083160613831206138316861383128613B7
:1009800083160612831206128316861283128612AB
:10099000AE010B138B138B1BCA2C0330B700E8304E
:1009A000B6000130B9009030B80055200B30B100CE
:1009B000B830B00031080E3C0318F22CFF3A031D8A
:1009C000E52C30086E3C0318F22C3108B7003008D3
:1009D000B600B9010A30B800552030080319B10338
:1009E000B003DA2C83160512831205120730B70004
:1009F000D030B600B901C830B80055200330B70078
:100A00008430B6000130B9009030B80055200B306A
:100A1000B1008630B00031080B3C031C212D031DB2
:100A2000152D3008B73C031C212D3108B7003008C4
:100A3000B600B9010A30B8005520B00A0319B10A4E
:100A40000B2D8316851183128511831605128312CF
:100A500005160F30B700A030B6000130B900903055
:100A6000B80055200330B700E830B600B901643053
:100A7000B800552083168513831285130B30B700F9
:100A8000B830B6000130B9009030B80055200430BD
:100A9000B400FA30B7007320B40B492D8316051249
:100AA0008312051683168511831285158316851307
:100AB000831285178316051383120517C0308B0424
:100AC0002A08023C031D822D831606138312061387
:100AD000831686138312861301082B02031C792DBB
:100AE0008316861283128612831606128312061646
:100AF000812D831606128312061283168612831224
:100B000086129F2D831606128312061283168612F2
:100B10008312861201082B02031C972D831686135D
:100B20008312861383160613831206179F2D8316CE
:100B30000613831206138316861383128613CB2B98
:020B4000630050
:04400E00383FFC3FFC
:00000001FF
;PIC16F88
/roboti/istrobot/merkur/PIC16F88/MerkurU/tank.LST
0,0 → 1,1740
CCS PCM C Compiler, Version 3.221, 27853 18-VI-05 13:30
 
Filename: D:\KAKLIK\programy\PIC_C\roboti\merkur\PIC16F88\MerkurU\tank.LST
 
ROM used: 1441 words (35%)
Largest free fragment is 2048
RAM used: 27 (15%) at main() level
34 (19%) worst case
Stack: 4 worst case (3 in main + 1 for interrupts)
 
*
0000: MOVLW 00
0001: MOVWF 0A
0002: GOTO 2D1
0003: NOP
0004: MOVWF 7F
0005: SWAPF 03,W
0006: CLRF 03
0007: MOVWF 21
0008: MOVF 7F,W
0009: MOVWF 20
000A: MOVF 0A,W
000B: MOVWF 28
000C: CLRF 0A
000D: SWAPF 20,F
000E: MOVF 04,W
000F: MOVWF 22
0010: MOVF 77,W
0011: MOVWF 23
0012: MOVF 78,W
0013: MOVWF 24
0014: MOVF 79,W
0015: MOVWF 25
0016: MOVF 7A,W
0017: MOVWF 26
0018: MOVF 7B,W
0019: MOVWF 27
001A: BCF 03.7
001B: BCF 03.5
001C: MOVLW 8C
001D: MOVWF 04
001E: BTFSS 00.1
001F: GOTO 022
0020: BTFSC 0C.1
0021: GOTO 035
0022: MOVF 22,W
0023: MOVWF 04
0024: MOVF 23,W
0025: MOVWF 77
0026: MOVF 24,W
0027: MOVWF 78
0028: MOVF 25,W
0029: MOVWF 79
002A: MOVF 26,W
002B: MOVWF 7A
002C: MOVF 27,W
002D: MOVWF 7B
002E: MOVF 28,W
002F: MOVWF 0A
0030: SWAPF 21,W
0031: MOVWF 03
0032: SWAPF 7F,F
0033: SWAPF 7F,W
0034: RETFIE
0035: BCF 0A.3
0036: GOTO 037
.................... // Program pro predvadeni schopnosti robota Merkur
.................... //------------------------------------------------
....................
.................... #include "tank.h"
.................... #include <16F88.h>
.................... //////// Standard Header file for the PIC16F88 device ////////////////
.................... #device PIC16F88
.................... #list
....................
.................... #device adc=8
.................... #fuses NOWDT,INTRC_IO, NOPUT, MCLR, NOBROWNOUT, NOLVP, NOCPD, NOWRT, NODEBUG, NOPROTECT, NOFCMEN, NOIESO
.................... #use delay(clock=4000000)
*
0042: MOVLW 12
0043: SUBWF 3C,F
0044: BTFSS 03.0
0045: GOTO 054
0046: MOVLW 3C
0047: MOVWF 04
0048: MOVLW FC
0049: ANDWF 00,F
004A: BCF 03.0
004B: RRF 00,F
004C: RRF 00,F
004D: MOVF 00,W
004E: BTFSC 03.2
004F: GOTO 054
0050: GOTO 052
0051: NOP
0052: DECFSZ 00,F
0053: GOTO 051
0054: RETLW 00
*
0073: MOVLW 37
0074: MOVWF 04
0075: MOVF 00,W
0076: BTFSC 03.2
0077: GOTO 087
0078: MOVLW 01
0079: MOVWF 78
007A: CLRF 77
007B: DECFSZ 77,F
007C: GOTO 07B
007D: DECFSZ 78,F
007E: GOTO 07A
007F: MOVLW 4A
0080: MOVWF 77
0081: DECFSZ 77,F
0082: GOTO 081
0083: NOP
0084: NOP
0085: DECFSZ 00,F
0086: GOTO 078
0087: RETLW 00
....................
....................
....................
.................... unsigned int8 sensors; // pomocna promenna pro cteni cidel na caru
.................... unsigned int8 line; // na ktere strane byla detekovana cara
.................... unsigned int8 speed; // rychlost zataceni
.................... unsigned int8 last; // kde byla cara, kdyz byly minule cidla mimo
.................... unsigned int8 rovinka; // pocitadlo pro zjisteni rovneho useku
.................... int cirkus; // pocitadlo, po kolika akcich se ma delat cirkus
.................... int1 BW; // urcuje, jestli je cara cerno/bila nebo
.................... // bilo/cerna (true = bila cara, cerny podklad)
....................
.................... // Konstanty pro dynamiku pohybu
.................... #define T_DIRA 120 // po jakem case zataceni se detekuje dira
.................... #define FW_POMALU 170 // trochu mimo caru vnitrni pas
.................... #define FW_ZATACKA 200 // rychlost vnejsiho kola pri zataceni
.................... #define FW_STREDNE 190 // trochu mimo caru vnejsi pas
.................... #define COUVANI 750 // couvnuti zpet na caru, po detekci diry
.................... #define MAX_ROVINKA (255-FW_STREDNE)
.................... #define TRESHOLD 15 // rozhodovaci uroven komparatoru, 0xF = 0.75*Vdd
.................... #define BUMPER_TRESHOLD 128 // rozhodovaci uroven cidla na prekazku
....................
.................... //motory //Napred vypnout potom zapnout!
.................... #define FR output_low(PIN_B5); output_high(PIN_B4) // Vpred
.................... #define FL output_low(PIN_B7); output_high(PIN_B6)
.................... #define BR output_low(PIN_B4); output_high(PIN_B5) // Vzad
.................... #define BL output_low(PIN_B6); output_high(PIN_B7)
.................... #define STOPR output_low(PIN_B4);output_low(PIN_B5) // Zastav
.................... #define STOPL output_low(PIN_B6);output_low(PIN_B7)
....................
.................... #define L 0b10 // left
.................... #define R 0b01 // right
.................... #define S 0b11 // straight
....................
.................... //cidla
.................... #define RSENSOR (BW != C2OUT) // Senzory na caru
.................... #define LSENSOR (BW != C1OUT)
.................... #define BUMPER sAN2 // Senzor na cihlu
....................
.................... #define DIAG_SERVO PIN_B3 // Propojka pro diagnosticky mod
.................... #define DIAG_SENSORS PIN_B2 // Propojka pro diagnosticky mod
.................... #define BARVY PIN_B1 // Propojka pro nastaveni barvy cary
....................
.................... #define SPEAKER PIN_B0 // vystup pro pipak
....................
.................... #define LED1 PIN_A4 // LEDky
.................... #define LED2 PIN_A3
.................... #define LED3 PIN_A7
.................... #define LED4 PIN_A6
....................
.................... // makro pro PWM
.................... #define GO(motor, direction, power) if(get_timer0()<=power) \
.................... {direction##motor;} else {stop##motor;}
....................
.................... #int_TIMER2
.................... void TIMER2_isr() // obsluha zrychlovani
.................... {
.................... if (speed<255) speed++;
*
0037: INCFSZ 2B,W
0038: GOTO 03A
0039: GOTO 03B
003A: INCF 2B,F
.................... if (rovinka<MAX_ROVINKA) rovinka++;
003B: MOVF 2D,W
003C: SUBLW 40
003D: BTFSC 03.0
003E: INCF 2D,F
.................... }
....................
.................... // Primitivni Pipani
003F: BCF 0C.1
0040: BCF 0A.3
0041: GOTO 022
.................... void beep(unsigned int16 period, unsigned int16 length)
.................... {
.................... unsigned int16 nn;
....................
.................... for(nn=length; nn>0; nn--)
*
0055: MOVF 39,W
0056: MOVWF 3B
0057: MOVF 38,W
0058: MOVWF 3A
0059: MOVF 3A,F
005A: BTFSS 03.2
005B: GOTO 05F
005C: MOVF 3B,F
005D: BTFSC 03.2
005E: GOTO 072
.................... {
.................... output_high(SPEAKER);
005F: BSF 03.5
0060: BCF 06.0
0061: BCF 03.5
0062: BSF 06.0
.................... delay_us(period);
0063: MOVF 36,W
0064: MOVWF 3C
0065: CALL 042
.................... output_low(SPEAKER);
0066: BSF 03.5
0067: BCF 06.0
0068: BCF 03.5
0069: BCF 06.0
.................... delay_us(period);
006A: MOVF 36,W
006B: MOVWF 3C
006C: CALL 042
.................... }
006D: MOVF 3A,W
006E: BTFSC 03.2
006F: DECF 3B,F
0070: DECF 3A,F
0071: GOTO 059
.................... }
0072: RETLW 00
.................... /******************************************************************************/
.................... void diagnostika()
.................... {
.................... unsigned int16 n;
....................
.................... while (input(DIAG_SERVO)) // Propojka, ktera spousti diagnostiku
.................... {
*
0088: BSF 03.5
0089: BSF 06.3
008A: BCF 03.5
008B: BTFSS 06.3
008C: GOTO 1B3
.................... for (n=500; n<800; n+=100)
008D: MOVLW 01
008E: MOVWF 35
008F: MOVLW F4
0090: MOVWF 34
0091: MOVF 35,W
0092: SUBLW 03
0093: BTFSS 03.0
0094: GOTO 0A9
0095: BTFSS 03.2
0096: GOTO 09B
0097: MOVF 34,W
0098: SUBLW 1F
0099: BTFSS 03.0
009A: GOTO 0A9
.................... {
.................... beep(n,n); //beep UP
009B: MOVF 35,W
009C: MOVWF 37
009D: MOVF 34,W
009E: MOVWF 36
009F: MOVF 35,W
00A0: MOVWF 39
00A1: MOVF 34,W
00A2: MOVWF 38
00A3: CALL 055
.................... };
00A4: MOVLW 64
00A5: ADDWF 34,F
00A6: BTFSC 03.0
00A7: INCF 35,F
00A8: GOTO 091
.................... Delay_ms(1000);
00A9: MOVLW 04
00AA: MOVWF 36
00AB: MOVLW FA
00AC: MOVWF 37
00AD: CALL 073
00AE: DECFSZ 36,F
00AF: GOTO 0AB
.................... //zastav vse
.................... STOPL; STOPR;
00B0: BSF 03.5
00B1: BCF 06.6
00B2: BCF 03.5
00B3: BCF 06.6
00B4: BSF 03.5
00B5: BCF 06.7
00B6: BCF 03.5
00B7: BCF 06.7
00B8: BSF 03.5
00B9: BCF 06.4
00BA: BCF 03.5
00BB: BCF 06.4
00BC: BSF 03.5
00BD: BCF 06.5
00BE: BCF 03.5
00BF: BCF 06.5
.................... //pravy pas
.................... FR; Delay_ms(1000); STOPR; Delay_ms(1000);
00C0: BSF 03.5
00C1: BCF 06.5
00C2: BCF 03.5
00C3: BCF 06.5
00C4: BSF 03.5
00C5: BCF 06.4
00C6: BCF 03.5
00C7: BSF 06.4
00C8: MOVLW 04
00C9: MOVWF 36
00CA: MOVLW FA
00CB: MOVWF 37
00CC: CALL 073
00CD: DECFSZ 36,F
00CE: GOTO 0CA
00CF: BSF 03.5
00D0: BCF 06.4
00D1: BCF 03.5
00D2: BCF 06.4
00D3: BSF 03.5
00D4: BCF 06.5
00D5: BCF 03.5
00D6: BCF 06.5
00D7: MOVLW 04
00D8: MOVWF 36
00D9: MOVLW FA
00DA: MOVWF 37
00DB: CALL 073
00DC: DECFSZ 36,F
00DD: GOTO 0D9
.................... BR; Delay_ms(1000); STOPR; Delay_ms(1000);
00DE: BSF 03.5
00DF: BCF 06.4
00E0: BCF 03.5
00E1: BCF 06.4
00E2: BSF 03.5
00E3: BCF 06.5
00E4: BCF 03.5
00E5: BSF 06.5
00E6: MOVLW 04
00E7: MOVWF 36
00E8: MOVLW FA
00E9: MOVWF 37
00EA: CALL 073
00EB: DECFSZ 36,F
00EC: GOTO 0E8
00ED: BSF 03.5
00EE: BCF 06.4
00EF: BCF 03.5
00F0: BCF 06.4
00F1: BSF 03.5
00F2: BCF 06.5
00F3: BCF 03.5
00F4: BCF 06.5
00F5: MOVLW 04
00F6: MOVWF 36
00F7: MOVLW FA
00F8: MOVWF 37
00F9: CALL 073
00FA: DECFSZ 36,F
00FB: GOTO 0F7
.................... Beep(880,100); Delay_ms(1000);
00FC: MOVLW 03
00FD: MOVWF 37
00FE: MOVLW 70
00FF: MOVWF 36
0100: CLRF 39
0101: MOVLW 64
0102: MOVWF 38
0103: CALL 055
0104: MOVLW 04
0105: MOVWF 36
0106: MOVLW FA
0107: MOVWF 37
0108: CALL 073
0109: DECFSZ 36,F
010A: GOTO 106
.................... //levy pas
.................... FL; Delay_ms(1000); STOPL; Delay_ms(1000);
010B: BSF 03.5
010C: BCF 06.7
010D: BCF 03.5
010E: BCF 06.7
010F: BSF 03.5
0110: BCF 06.6
0111: BCF 03.5
0112: BSF 06.6
0113: MOVLW 04
0114: MOVWF 36
0115: MOVLW FA
0116: MOVWF 37
0117: CALL 073
0118: DECFSZ 36,F
0119: GOTO 115
011A: BSF 03.5
011B: BCF 06.6
011C: BCF 03.5
011D: BCF 06.6
011E: BSF 03.5
011F: BCF 06.7
0120: BCF 03.5
0121: BCF 06.7
0122: MOVLW 04
0123: MOVWF 36
0124: MOVLW FA
0125: MOVWF 37
0126: CALL 073
0127: DECFSZ 36,F
0128: GOTO 124
.................... BL; Delay_ms(1000); STOPL; Delay_ms(1000);
0129: BSF 03.5
012A: BCF 06.6
012B: BCF 03.5
012C: BCF 06.6
012D: BSF 03.5
012E: BCF 06.7
012F: BCF 03.5
0130: BSF 06.7
0131: MOVLW 04
0132: MOVWF 36
0133: MOVLW FA
0134: MOVWF 37
0135: CALL 073
0136: DECFSZ 36,F
0137: GOTO 133
0138: BSF 03.5
0139: BCF 06.6
013A: BCF 03.5
013B: BCF 06.6
013C: BSF 03.5
013D: BCF 06.7
013E: BCF 03.5
013F: BCF 06.7
0140: MOVLW 04
0141: MOVWF 36
0142: MOVLW FA
0143: MOVWF 37
0144: CALL 073
0145: DECFSZ 36,F
0146: GOTO 142
.................... Beep(880,100); Delay_ms(1000);
0147: MOVLW 03
0148: MOVWF 37
0149: MOVLW 70
014A: MOVWF 36
014B: CLRF 39
014C: MOVLW 64
014D: MOVWF 38
014E: CALL 055
014F: MOVLW 04
0150: MOVWF 36
0151: MOVLW FA
0152: MOVWF 37
0153: CALL 073
0154: DECFSZ 36,F
0155: GOTO 151
.................... //oba pasy
.................... FL; FR; Delay_ms(1000); STOPL; STOPR; Delay_ms(1000);
0156: BSF 03.5
0157: BCF 06.7
0158: BCF 03.5
0159: BCF 06.7
015A: BSF 03.5
015B: BCF 06.6
015C: BCF 03.5
015D: BSF 06.6
015E: BSF 03.5
015F: BCF 06.5
0160: BCF 03.5
0161: BCF 06.5
0162: BSF 03.5
0163: BCF 06.4
0164: BCF 03.5
0165: BSF 06.4
0166: MOVLW 04
0167: MOVWF 36
0168: MOVLW FA
0169: MOVWF 37
016A: CALL 073
016B: DECFSZ 36,F
016C: GOTO 168
016D: BSF 03.5
016E: BCF 06.6
016F: BCF 03.5
0170: BCF 06.6
0171: BSF 03.5
0172: BCF 06.7
0173: BCF 03.5
0174: BCF 06.7
0175: BSF 03.5
0176: BCF 06.4
0177: BCF 03.5
0178: BCF 06.4
0179: BSF 03.5
017A: BCF 06.5
017B: BCF 03.5
017C: BCF 06.5
017D: MOVLW 04
017E: MOVWF 36
017F: MOVLW FA
0180: MOVWF 37
0181: CALL 073
0182: DECFSZ 36,F
0183: GOTO 17F
.................... BL; BR; Delay_ms(1000); STOPL; STOPR; Delay_ms(1000);
0184: BSF 03.5
0185: BCF 06.6
0186: BCF 03.5
0187: BCF 06.6
0188: BSF 03.5
0189: BCF 06.7
018A: BCF 03.5
018B: BSF 06.7
018C: BSF 03.5
018D: BCF 06.4
018E: BCF 03.5
018F: BCF 06.4
0190: BSF 03.5
0191: BCF 06.5
0192: BCF 03.5
0193: BSF 06.5
0194: MOVLW 04
0195: MOVWF 36
0196: MOVLW FA
0197: MOVWF 37
0198: CALL 073
0199: DECFSZ 36,F
019A: GOTO 196
019B: BSF 03.5
019C: BCF 06.6
019D: BCF 03.5
019E: BCF 06.6
019F: BSF 03.5
01A0: BCF 06.7
01A1: BCF 03.5
01A2: BCF 06.7
01A3: BSF 03.5
01A4: BCF 06.4
01A5: BCF 03.5
01A6: BCF 06.4
01A7: BSF 03.5
01A8: BCF 06.5
01A9: BCF 03.5
01AA: BCF 06.5
01AB: MOVLW 04
01AC: MOVWF 36
01AD: MOVLW FA
01AE: MOVWF 37
01AF: CALL 073
01B0: DECFSZ 36,F
01B1: GOTO 1AD
.................... };
01B2: GOTO 088
.................... while (input(DIAG_SENSORS)) // spusteni diagnostiky cidel
.................... {
01B3: BSF 03.5
01B4: BSF 06.2
01B5: BCF 03.5
01B6: BTFSS 06.2
01B7: GOTO 1F6
.................... if (RSENSOR) beep(1000,200);
01B8: CLRF 77
01B9: BSF 03.5
01BA: BTFSC 1C.7
01BB: BSF 77.0
01BC: BCF 03.5
01BD: MOVF 2F,W
01BE: XORWF 77,W
01BF: ANDLW 01
01C0: BTFSC 03.2
01C1: GOTO 1CA
01C2: MOVLW 03
01C3: MOVWF 37
01C4: MOVLW E8
01C5: MOVWF 36
01C6: CLRF 39
01C7: MOVLW C8
01C8: MOVWF 38
01C9: CALL 055
.................... Delay_ms(200);
01CA: MOVLW C8
01CB: MOVWF 37
01CC: CALL 073
.................... if (LSENSOR) beep(2000,300);
01CD: CLRF 77
01CE: BSF 03.5
01CF: BTFSC 1C.6
01D0: BSF 77.0
01D1: BCF 03.5
01D2: MOVF 2F,W
01D3: XORWF 77,W
01D4: ANDLW 01
01D5: BTFSC 03.2
01D6: GOTO 1E0
01D7: MOVLW 07
01D8: MOVWF 37
01D9: MOVLW D0
01DA: MOVWF 36
01DB: MOVLW 01
01DC: MOVWF 39
01DD: MOVLW 2C
01DE: MOVWF 38
01DF: CALL 055
.................... Delay_ms(200);
01E0: MOVLW C8
01E1: MOVWF 37
01E2: CALL 073
.................... if ((read_adc(ADC_READ_ONLY)<BUMPER_TRESHOLD)) beep(3000,400);
01E3: BTFSC 1F.2
01E4: GOTO 1E3
01E5: MOVF 1E,W
01E6: SUBLW 7F
01E7: BTFSS 03.0
01E8: GOTO 1F2
01E9: MOVLW 0B
01EA: MOVWF 37
01EB: MOVLW B8
01EC: MOVWF 36
01ED: MOVLW 01
01EE: MOVWF 39
01EF: MOVLW 90
01F0: MOVWF 38
01F1: CALL 055
.................... Delay_ms(200);
01F2: MOVLW C8
01F3: MOVWF 37
01F4: CALL 073
.................... };
01F5: GOTO 1B3
.................... }
01F6: BCF 0A.3
01F7: GOTO 378 (RETURN)
.................... ///////////////////////////////////////////////////////////////////////////////
.................... void OtocSe() // otoci se zpet, kdyz je prekazka
.................... {
.................... unsigned int16 n;
....................
.................... BL; BR; // cukni zpatky
01F8: BSF 03.5
01F9: BCF 06.6
01FA: BCF 03.5
01FB: BCF 06.6
01FC: BSF 03.5
01FD: BCF 06.7
01FE: BCF 03.5
01FF: BSF 06.7
0200: BSF 03.5
0201: BCF 06.4
0202: BCF 03.5
0203: BCF 06.4
0204: BSF 03.5
0205: BCF 06.5
0206: BCF 03.5
0207: BSF 06.5
.................... Delay_ms(200);
0208: MOVLW C8
0209: MOVWF 37
020A: CALL 073
.................... STOPR;STOPL;
020B: BSF 03.5
020C: BCF 06.4
020D: BCF 03.5
020E: BCF 06.4
020F: BSF 03.5
0210: BCF 06.5
0211: BCF 03.5
0212: BCF 06.5
0213: BSF 03.5
0214: BCF 06.6
0215: BCF 03.5
0216: BCF 06.6
0217: BSF 03.5
0218: BCF 06.7
0219: BCF 03.5
021A: BCF 06.7
.................... beep(800,400);
021B: MOVLW 03
021C: MOVWF 37
021D: MOVLW 20
021E: MOVWF 36
021F: MOVLW 01
0220: MOVWF 39
0221: MOVLW 90
0222: MOVWF 38
0223: CALL 055
.................... beep(2000,1000);
0224: MOVLW 07
0225: MOVWF 37
0226: MOVLW D0
0227: MOVWF 36
0228: MOVLW 03
0229: MOVWF 39
022A: MOVLW E8
022B: MOVWF 38
022C: CALL 055
.................... output_low(LED4);
022D: BSF 03.5
022E: BCF 05.6
022F: BCF 03.5
0230: BCF 05.6
.................... beep(900,400);
0231: MOVLW 03
0232: MOVWF 37
0233: MOVLW 84
0234: MOVWF 36
0235: MOVLW 01
0236: MOVWF 39
0237: MOVLW 90
0238: MOVWF 38
0239: CALL 055
.................... output_low(LED1);
023A: BSF 03.5
023B: BCF 05.4
023C: BCF 03.5
023D: BCF 05.4
....................
.................... BR; FL; Delay_ms(100); // otoc se 30° do prava
023E: BSF 03.5
023F: BCF 06.4
0240: BCF 03.5
0241: BCF 06.4
0242: BSF 03.5
0243: BCF 06.5
0244: BCF 03.5
0245: BSF 06.5
0246: BSF 03.5
0247: BCF 06.7
0248: BCF 03.5
0249: BCF 06.7
024A: BSF 03.5
024B: BCF 06.6
024C: BCF 03.5
024D: BSF 06.6
024E: MOVLW 64
024F: MOVWF 37
0250: CALL 073
.................... STOPL; STOPR;
0251: BSF 03.5
0252: BCF 06.6
0253: BCF 03.5
0254: BCF 06.6
0255: BSF 03.5
0256: BCF 06.7
0257: BCF 03.5
0258: BCF 06.7
0259: BSF 03.5
025A: BCF 06.4
025B: BCF 03.5
025C: BCF 06.4
025D: BSF 03.5
025E: BCF 06.5
025F: BCF 03.5
0260: BCF 06.5
.................... beep(1000,1000);
0261: MOVLW 03
0262: MOVWF 37
0263: MOVLW E8
0264: MOVWF 36
0265: MOVLW 03
0266: MOVWF 39
0267: MOVLW E8
0268: MOVWF 38
0269: CALL 055
.................... output_low(LED3);
026A: BSF 03.5
026B: BCF 05.7
026C: BCF 03.5
026D: BCF 05.7
....................
.................... BR; FL;
026E: BSF 03.5
026F: BCF 06.4
0270: BCF 03.5
0271: BCF 06.4
0272: BSF 03.5
0273: BCF 06.5
0274: BCF 03.5
0275: BSF 06.5
0276: BSF 03.5
0277: BCF 06.7
0278: BCF 03.5
0279: BCF 06.7
027A: BSF 03.5
027B: BCF 06.6
027C: BCF 03.5
027D: BSF 06.6
.................... for(n=40000;n>0;n--) // toc se, dokud nenarazis na caru
027E: MOVLW 9C
027F: MOVWF 35
0280: MOVLW 40
0281: MOVWF 34
0282: MOVF 34,F
0283: BTFSS 03.2
0284: GOTO 288
0285: MOVF 35,F
0286: BTFSC 03.2
0287: GOTO 2B0
.................... {
.................... line = RSENSOR; // cteni senzoru na caru
0288: CLRF 77
0289: BSF 03.5
028A: BTFSC 1C.7
028B: BSF 77.0
028C: BCF 03.5
028D: MOVF 2F,W
028E: XORWF 77,W
028F: ANDLW 01
0290: BTFSS 03.2
0291: GOTO 294
0292: MOVLW 00
0293: GOTO 295
0294: MOVLW 01
0295: MOVWF 2A
.................... line |= LSENSOR << 1;
0296: CLRF 77
0297: BSF 03.5
0298: BTFSC 1C.6
0299: BSF 77.0
029A: BCF 03.5
029B: MOVF 2F,W
029C: XORWF 77,W
029D: ANDLW 01
029E: BTFSS 03.2
029F: GOTO 2A2
02A0: MOVLW 00
02A1: GOTO 2A3
02A2: MOVLW 01
02A3: MOVWF 77
02A4: BCF 03.0
02A5: RLF 77,F
02A6: MOVF 77,W
02A7: IORWF 2A,F
.................... if (line!=0) break;
02A8: MOVF 2A,F
02A9: BTFSS 03.2
02AA: GOTO 2B0
.................... }
02AB: MOVF 34,W
02AC: BTFSC 03.2
02AD: DECF 35,F
02AE: DECF 34,F
02AF: GOTO 282
.................... STOPR; STOPL;
02B0: BSF 03.5
02B1: BCF 06.4
02B2: BCF 03.5
02B3: BCF 06.4
02B4: BSF 03.5
02B5: BCF 06.5
02B6: BCF 03.5
02B7: BCF 06.5
02B8: BSF 03.5
02B9: BCF 06.6
02BA: BCF 03.5
02BB: BCF 06.6
02BC: BSF 03.5
02BD: BCF 06.7
02BE: BCF 03.5
02BF: BCF 06.7
.................... output_high(LED1); output_high(LED3); output_high(LED4);
02C0: BSF 03.5
02C1: BCF 05.4
02C2: BCF 03.5
02C3: BSF 05.4
02C4: BSF 03.5
02C5: BCF 05.7
02C6: BCF 03.5
02C7: BSF 05.7
02C8: BSF 03.5
02C9: BCF 05.6
02CA: BCF 03.5
02CB: BSF 05.6
....................
.................... line=L; // caru jsme prejeli, tak je vlevo
02CC: MOVLW 02
02CD: MOVWF 2A
.................... cirkus=0;
02CE: CLRF 2E
.................... }
02CF: BCF 0A.3
02D0: GOTO 3F1 (RETURN)
....................
....................
.................... void main()
.................... {
02D1: CLRF 04
02D2: MOVLW 1F
02D3: ANDWF 03,F
02D4: BSF 03.5
02D5: BCF 1F.4
02D6: BCF 1F.5
02D7: MOVF 1B,W
02D8: ANDLW 80
02D9: MOVWF 1B
02DA: MOVLW 07
02DB: MOVWF 1C
02DC: MOVF 1C,W
02DD: BCF 03.5
02DE: BCF 0D.6
02DF: MOVLW 60
02E0: BSF 03.5
02E1: MOVWF 0F
.................... unsigned int16 n; // pro FOR
.................... unsigned int16 i;
....................
.................... STOPL; STOPR; // prepne vystupy na ovladani motoru na output a zastavi
02E2: BCF 06.6
02E3: BCF 03.5
02E4: BCF 06.6
02E5: BSF 03.5
02E6: BCF 06.7
02E7: BCF 03.5
02E8: BCF 06.7
02E9: BSF 03.5
02EA: BCF 06.4
02EB: BCF 03.5
02EC: BCF 06.4
02ED: BSF 03.5
02EE: BCF 06.5
02EF: BCF 03.5
02F0: BCF 06.5
....................
.................... setup_oscillator(OSC_4MHZ|OSC_INTRC); // 4 MHz interni RC oscilator
02F1: MOVLW 62
02F2: BSF 03.5
02F3: MOVWF 0F
....................
.................... port_b_pullups(TRUE); // pullups pro piano na diagnostiku
02F4: BCF 01.7
.................... setup_spi(FALSE);
02F5: BCF 03.5
02F6: BCF 14.5
02F7: BSF 03.5
02F8: BCF 06.2
02F9: BSF 06.1
02FA: BCF 06.4
02FB: MOVLW 00
02FC: BCF 03.5
02FD: MOVWF 14
02FE: BSF 03.5
02FF: MOVWF 14
.................... setup_timer_0(RTCC_INTERNAL|RTCC_DIV_1); // Casovac pro PWM
0300: MOVF 01,W
0301: ANDLW C7
0302: IORLW 08
0303: MOVWF 01
....................
.................... setup_timer_2(T2_DIV_BY_4,255,10); // Casovac pro regulaci
0304: MOVLW 48
0305: MOVWF 78
0306: IORLW 05
0307: BCF 03.5
0308: MOVWF 12
0309: MOVLW FF
030A: BSF 03.5
030B: MOVWF 12
.................... // preruseni kazdych 10ms
.................... setup_adc_ports(BUMPER|VSS_VDD); // nastaveni A/D prevodniku pro naraznik
030C: BCF 1F.4
030D: BCF 1F.5
030E: MOVF 1B,W
030F: ANDLW 80
0310: IORLW 04
0311: MOVWF 1B
.................... setup_adc(ADC_CLOCK_INTERNAL);
0312: BCF 1F.6
0313: BCF 03.5
0314: BSF 1F.6
0315: BSF 1F.7
0316: BSF 03.5
0317: BCF 1F.7
0318: BCF 03.5
0319: BSF 1F.0
.................... set_adc_channel(2);
031A: MOVLW 10
031B: MOVWF 78
031C: MOVF 1F,W
031D: ANDLW C7
031E: IORWF 78,W
031F: MOVWF 1F
.................... setup_timer_1(T1_INTERNAL|T1_DIV_BY_1); // Casovac pro naraznik
0320: MOVLW 85
0321: MOVWF 10
.................... setup_ccp1(CCP_COMPARE_RESET_TIMER);
0322: BSF 03.5
0323: BSF 06.3
0324: MOVLW 0B
0325: BCF 03.5
0326: MOVWF 17
.................... CCP_1=(2^10)-1; // prevod kazdou 1ms
0327: CLRF 16
0328: MOVLW 07
0329: MOVWF 15
....................
.................... output_low(LED1); output_low(LED2); output_low(LED3); output_low(LED4);
032A: BSF 03.5
032B: BCF 05.4
032C: BCF 03.5
032D: BCF 05.4
032E: BSF 03.5
032F: BCF 05.3
0330: BCF 03.5
0331: BCF 05.3
0332: BSF 03.5
0333: BCF 05.7
0334: BCF 03.5
0335: BCF 05.7
0336: BSF 03.5
0337: BCF 05.6
0338: BCF 03.5
0339: BCF 05.6
....................
.................... setup_comparator(A0_VR_A1_VR); // inicializace komparatoru pro cidla cary
033A: MOVLW 02
033B: BSF 03.5
033C: MOVWF 1C
033D: MOVF 05,W
033E: IORLW 03
033F: MOVWF 05
0340: MOVLW 03
0341: MOVWF 77
0342: DECFSZ 77,F
0343: GOTO 342
0344: MOVF 1C,W
0345: BCF 03.5
0346: BCF 0D.6
.................... setup_vref(VREF_HIGH|TRESHOLD); // 32 kroku od 0.25 do 0.75 Vdd
0347: MOVLW 8F
0348: BSF 03.5
0349: MOVWF 1D
....................
.................... Beep(1000,200); //double beep
034A: MOVLW 03
034B: BCF 03.5
034C: MOVWF 37
034D: MOVLW E8
034E: MOVWF 36
034F: CLRF 39
0350: MOVLW C8
0351: MOVWF 38
0352: CALL 055
.................... Delay_ms(50);
0353: MOVLW 32
0354: MOVWF 37
0355: CALL 073
.................... Beep(1000,200);
0356: MOVLW 03
0357: MOVWF 37
0358: MOVLW E8
0359: MOVWF 36
035A: CLRF 39
035B: MOVLW C8
035C: MOVWF 38
035D: CALL 055
.................... Delay_ms(1000); // 1s
035E: MOVLW 04
035F: MOVWF 34
0360: MOVLW FA
0361: MOVWF 37
0362: CALL 073
0363: DECFSZ 34,F
0364: GOTO 360
....................
.................... // povoleni rizeni rychlosti zataceni pres preruseni
.................... enable_interrupts(INT_TIMER2);
0365: BSF 03.5
0366: BSF 0C.1
.................... enable_interrupts(GLOBAL);
0367: MOVLW C0
0368: BCF 03.5
0369: IORWF 0B,F
....................
.................... /*---------------------------------------------------------------------------*/
.................... sensors=S;
036A: MOVLW 03
036B: MOVWF 29
.................... line=S;
036C: MOVWF 2A
.................... last=S;
036D: MOVWF 2C
.................... cirkus=0;
036E: CLRF 2E
.................... // movement=S;
.................... speed=FW_POMALU;
036F: MOVLW AA
0370: MOVWF 2B
....................
.................... BW=input(BARVY); // Jaka ma byt barva cary?
0371: BSF 03.5
0372: BSF 06.1
0373: BCF 03.5
0374: BCF 2F.0
0375: BTFSC 06.1
0376: BSF 2F.0
.................... diagnostika(); // Zkus, jestli nekdo nechce, diagnostiku
0377: GOTO 088
.................... Delay_ms(500);
0378: MOVLW 02
0379: MOVWF 34
037A: MOVLW FA
037B: MOVWF 37
037C: CALL 073
037D: DECFSZ 34,F
037E: GOTO 37A
....................
.................... output_high(LED1); Beep(1000,200); Delay_ms(500);
037F: BSF 03.5
0380: BCF 05.4
0381: BCF 03.5
0382: BSF 05.4
0383: MOVLW 03
0384: MOVWF 37
0385: MOVLW E8
0386: MOVWF 36
0387: CLRF 39
0388: MOVLW C8
0389: MOVWF 38
038A: CALL 055
038B: MOVLW 02
038C: MOVWF 34
038D: MOVLW FA
038E: MOVWF 37
038F: CALL 073
0390: DECFSZ 34,F
0391: GOTO 38D
.................... output_high(LED2); Beep(1000,200); Delay_ms(500);
0392: BSF 03.5
0393: BCF 05.3
0394: BCF 03.5
0395: BSF 05.3
0396: MOVLW 03
0397: MOVWF 37
0398: MOVLW E8
0399: MOVWF 36
039A: CLRF 39
039B: MOVLW C8
039C: MOVWF 38
039D: CALL 055
039E: MOVLW 02
039F: MOVWF 34
03A0: MOVLW FA
03A1: MOVWF 37
03A2: CALL 073
03A3: DECFSZ 34,F
03A4: GOTO 3A0
.................... output_high(LED3); Beep(1000,200); Delay_ms(500);
03A5: BSF 03.5
03A6: BCF 05.7
03A7: BCF 03.5
03A8: BSF 05.7
03A9: MOVLW 03
03AA: MOVWF 37
03AB: MOVLW E8
03AC: MOVWF 36
03AD: CLRF 39
03AE: MOVLW C8
03AF: MOVWF 38
03B0: CALL 055
03B1: MOVLW 02
03B2: MOVWF 34
03B3: MOVLW FA
03B4: MOVWF 37
03B5: CALL 073
03B6: DECFSZ 34,F
03B7: GOTO 3B3
.................... output_high(LED4); Beep(1000,200); Delay_ms(500);
03B8: BSF 03.5
03B9: BCF 05.6
03BA: BCF 03.5
03BB: BSF 05.6
03BC: MOVLW 03
03BD: MOVWF 37
03BE: MOVLW E8
03BF: MOVWF 36
03C0: CLRF 39
03C1: MOVLW C8
03C2: MOVWF 38
03C3: CALL 055
03C4: MOVLW 02
03C5: MOVWF 34
03C6: MOVLW FA
03C7: MOVWF 37
03C8: CALL 073
03C9: DECFSZ 34,F
03CA: GOTO 3C6
....................
.................... while(true) // hlavni smycka (jizda podle cary)
.................... {
.................... sensors = RSENSOR; // cteni senzoru na caru
03CB: CLRF 77
03CC: BSF 03.5
03CD: BTFSC 1C.7
03CE: BSF 77.0
03CF: BCF 03.5
03D0: MOVF 2F,W
03D1: XORWF 77,W
03D2: ANDLW 01
03D3: BTFSS 03.2
03D4: GOTO 3D7
03D5: MOVLW 00
03D6: GOTO 3D8
03D7: MOVLW 01
03D8: MOVWF 29
.................... sensors |= LSENSOR << 1;
03D9: CLRF 77
03DA: BSF 03.5
03DB: BTFSC 1C.6
03DC: BSF 77.0
03DD: BCF 03.5
03DE: MOVF 2F,W
03DF: XORWF 77,W
03E0: ANDLW 01
03E1: BTFSS 03.2
03E2: GOTO 3E5
03E3: MOVLW 00
03E4: GOTO 3E6
03E5: MOVLW 01
03E6: MOVWF 77
03E7: BCF 03.0
03E8: RLF 77,F
03E9: MOVF 77,W
03EA: IORWF 29,F
....................
.................... if (read_adc(ADC_READ_ONLY)<BUMPER_TRESHOLD) OtocSe();
03EB: BTFSC 1F.2
03EC: GOTO 3EB
03ED: MOVF 1E,W
03EE: SUBLW 7F
03EF: BTFSC 03.0
03F0: GOTO 1F8
....................
.................... switch (sensors) // zatacej podle toho, kde vidis caru
.................... {
03F1: MOVF 29,W
03F2: XORLW 03
03F3: BTFSC 03.2
03F4: GOTO 3FC
03F5: XORLW 01
03F6: BTFSC 03.2
03F7: GOTO 431
03F8: XORLW 03
03F9: BTFSC 03.2
03FA: GOTO 468
03FB: GOTO 49F
.................... case S: // rovne
.................... GO(L, F, FW_STREDNE+rovinka); GO(R, F, FW_STREDNE+rovinka);
03FC: MOVF 01,W
03FD: MOVWF 34
03FE: MOVLW BE
03FF: ADDWF 2D,W
0400: SUBWF 34,W
0401: BTFSC 03.2
0402: GOTO 405
0403: BTFSC 03.0
0404: GOTO 40E
0405: BSF 03.5
0406: BCF 06.7
0407: BCF 03.5
0408: BCF 06.7
0409: BSF 03.5
040A: BCF 06.6
040B: BCF 03.5
040C: BSF 06.6
040D: GOTO 416
040E: BSF 03.5
040F: BCF 06.6
0410: BCF 03.5
0411: BCF 06.6
0412: BSF 03.5
0413: BCF 06.7
0414: BCF 03.5
0415: BCF 06.7
0416: MOVF 01,W
0417: MOVWF 34
0418: MOVLW BE
0419: ADDWF 2D,W
041A: SUBWF 34,W
041B: BTFSC 03.2
041C: GOTO 41F
041D: BTFSC 03.0
041E: GOTO 428
041F: BSF 03.5
0420: BCF 06.5
0421: BCF 03.5
0422: BCF 06.5
0423: BSF 03.5
0424: BCF 06.4
0425: BCF 03.5
0426: BSF 06.4
0427: GOTO 430
0428: BSF 03.5
0429: BCF 06.4
042A: BCF 03.5
042B: BCF 06.4
042C: BSF 03.5
042D: BCF 06.5
042E: BCF 03.5
042F: BCF 06.5
.................... continue;
0430: GOTO 3CB
.................... case L: // trochu vlevo
.................... GO(L, F, FW_POMALU+rovinka); GO(R, F, FW_STREDNE+rovinka);
0431: MOVF 01,W
0432: MOVWF 34
0433: MOVLW AA
0434: ADDWF 2D,W
0435: SUBWF 34,W
0436: BTFSC 03.2
0437: GOTO 43A
0438: BTFSC 03.0
0439: GOTO 443
043A: BSF 03.5
043B: BCF 06.7
043C: BCF 03.5
043D: BCF 06.7
043E: BSF 03.5
043F: BCF 06.6
0440: BCF 03.5
0441: BSF 06.6
0442: GOTO 44B
0443: BSF 03.5
0444: BCF 06.6
0445: BCF 03.5
0446: BCF 06.6
0447: BSF 03.5
0448: BCF 06.7
0449: BCF 03.5
044A: BCF 06.7
044B: MOVF 01,W
044C: MOVWF 34
044D: MOVLW BE
044E: ADDWF 2D,W
044F: SUBWF 34,W
0450: BTFSC 03.2
0451: GOTO 454
0452: BTFSC 03.0
0453: GOTO 45D
0454: BSF 03.5
0455: BCF 06.5
0456: BCF 03.5
0457: BCF 06.5
0458: BSF 03.5
0459: BCF 06.4
045A: BCF 03.5
045B: BSF 06.4
045C: GOTO 465
045D: BSF 03.5
045E: BCF 06.4
045F: BCF 03.5
0460: BCF 06.4
0461: BSF 03.5
0462: BCF 06.5
0463: BCF 03.5
0464: BCF 06.5
.................... line=L;
0465: MOVLW 02
0466: MOVWF 2A
.................... continue;
0467: GOTO 3CB
.................... case R: // trochu vpravo
.................... GO(R, F, FW_POMALU+rovinka); GO(L, F, FW_STREDNE+rovinka);
0468: MOVF 01,W
0469: MOVWF 34
046A: MOVLW AA
046B: ADDWF 2D,W
046C: SUBWF 34,W
046D: BTFSC 03.2
046E: GOTO 471
046F: BTFSC 03.0
0470: GOTO 47A
0471: BSF 03.5
0472: BCF 06.5
0473: BCF 03.5
0474: BCF 06.5
0475: BSF 03.5
0476: BCF 06.4
0477: BCF 03.5
0478: BSF 06.4
0479: GOTO 482
047A: BSF 03.5
047B: BCF 06.4
047C: BCF 03.5
047D: BCF 06.4
047E: BSF 03.5
047F: BCF 06.5
0480: BCF 03.5
0481: BCF 06.5
0482: MOVF 01,W
0483: MOVWF 34
0484: MOVLW BE
0485: ADDWF 2D,W
0486: SUBWF 34,W
0487: BTFSC 03.2
0488: GOTO 48B
0489: BTFSC 03.0
048A: GOTO 494
048B: BSF 03.5
048C: BCF 06.7
048D: BCF 03.5
048E: BCF 06.7
048F: BSF 03.5
0490: BCF 06.6
0491: BCF 03.5
0492: BSF 06.6
0493: GOTO 49C
0494: BSF 03.5
0495: BCF 06.6
0496: BCF 03.5
0497: BCF 06.6
0498: BSF 03.5
0499: BCF 06.7
049A: BCF 03.5
049B: BCF 06.7
.................... line=R;
049C: MOVLW 01
049D: MOVWF 2A
.................... continue;
049E: GOTO 3CB
.................... default: // kdyz jsou obe cidla mimo caru, tak pokracuj dal
.................... };
.................... rovinka=0;
049F: CLRF 2D
....................
.................... if (last!=line) // pokud si prejel caru z jedne strany na druhou stranu,
04A0: MOVF 2A,W
04A1: SUBWF 2C,W
04A2: BTFSC 03.2
04A3: GOTO 560
.................... // tak zabrzdi
.................... {
.................... output_bit(LED1, !input(LED1));
04A4: BSF 03.5
04A5: BSF 05.4
04A6: BCF 03.5
04A7: BTFSS 05.4
04A8: GOTO 4AB
04A9: BCF 05.4
04AA: GOTO 4AC
04AB: BSF 05.4
04AC: BSF 03.5
04AD: BCF 05.4
.................... last=line;
04AE: BCF 03.5
04AF: MOVF 2A,W
04B0: MOVWF 2C
.................... speed=FW_ZATACKA;
04B1: MOVLW C8
04B2: MOVWF 2B
.................... cirkus++;
04B3: INCF 2E,F
.................... if (cirkus>8)
04B4: MOVF 2E,W
04B5: SUBLW 08
04B6: BTFSC 03.0
04B7: GOTO 560
.................... {
.................... STOPL; STOPR;
04B8: BSF 03.5
04B9: BCF 06.6
04BA: BCF 03.5
04BB: BCF 06.6
04BC: BSF 03.5
04BD: BCF 06.7
04BE: BCF 03.5
04BF: BCF 06.7
04C0: BSF 03.5
04C1: BCF 06.4
04C2: BCF 03.5
04C3: BCF 06.4
04C4: BSF 03.5
04C5: BCF 06.5
04C6: BCF 03.5
04C7: BCF 06.5
.................... cirkus=0;
04C8: CLRF 2E
.................... disable_interrupts(GLOBAL);
04C9: BCF 0B.6
04CA: BCF 0B.7
04CB: BTFSC 0B.7
04CC: GOTO 4CA
.................... beep(1000,400);
04CD: MOVLW 03
04CE: MOVWF 37
04CF: MOVLW E8
04D0: MOVWF 36
04D1: MOVLW 01
04D2: MOVWF 39
04D3: MOVLW 90
04D4: MOVWF 38
04D5: CALL 055
.................... for(n=3000; n>3950; n--) beep(n,10);
04D6: MOVLW 0B
04D7: MOVWF 31
04D8: MOVLW B8
04D9: MOVWF 30
04DA: MOVF 31,W
04DB: SUBLW 0E
04DC: BTFSC 03.0
04DD: GOTO 4F2
04DE: XORLW FF
04DF: BTFSS 03.2
04E0: GOTO 4E5
04E1: MOVF 30,W
04E2: SUBLW 6E
04E3: BTFSC 03.0
04E4: GOTO 4F2
04E5: MOVF 31,W
04E6: MOVWF 37
04E7: MOVF 30,W
04E8: MOVWF 36
04E9: CLRF 39
04EA: MOVLW 0A
04EB: MOVWF 38
04EC: CALL 055
04ED: MOVF 30,W
04EE: BTFSC 03.2
04EF: DECF 31,F
04F0: DECF 30,F
04F1: GOTO 4DA
.................... output_low(LED1);
04F2: BSF 03.5
04F3: BCF 05.4
04F4: BCF 03.5
04F5: BCF 05.4
.................... beep(2000,200);
04F6: MOVLW 07
04F7: MOVWF 37
04F8: MOVLW D0
04F9: MOVWF 36
04FA: CLRF 39
04FB: MOVLW C8
04FC: MOVWF 38
04FD: CALL 055
.................... beep(900,400);
04FE: MOVLW 03
04FF: MOVWF 37
0500: MOVLW 84
0501: MOVWF 36
0502: MOVLW 01
0503: MOVWF 39
0504: MOVLW 90
0505: MOVWF 38
0506: CALL 055
.................... for(n=2950; n<3000; n++) beep(n,10);
0507: MOVLW 0B
0508: MOVWF 31
0509: MOVLW 86
050A: MOVWF 30
050B: MOVF 31,W
050C: SUBLW 0B
050D: BTFSS 03.0
050E: GOTO 521
050F: BTFSS 03.2
0510: GOTO 515
0511: MOVF 30,W
0512: SUBLW B7
0513: BTFSS 03.0
0514: GOTO 521
0515: MOVF 31,W
0516: MOVWF 37
0517: MOVF 30,W
0518: MOVWF 36
0519: CLRF 39
051A: MOVLW 0A
051B: MOVWF 38
051C: CALL 055
051D: INCF 30,F
051E: BTFSC 03.2
051F: INCF 31,F
0520: GOTO 50B
.................... output_low(LED2);
0521: BSF 03.5
0522: BCF 05.3
0523: BCF 03.5
0524: BCF 05.3
.................... output_high(LED1);
0525: BSF 03.5
0526: BCF 05.4
0527: BCF 03.5
0528: BSF 05.4
.................... beep(4000,400);
0529: MOVLW 0F
052A: MOVWF 37
052B: MOVLW A0
052C: MOVWF 36
052D: MOVLW 01
052E: MOVWF 39
052F: MOVLW 90
0530: MOVWF 38
0531: CALL 055
.................... beep(1000,100);
0532: MOVLW 03
0533: MOVWF 37
0534: MOVLW E8
0535: MOVWF 36
0536: CLRF 39
0537: MOVLW 64
0538: MOVWF 38
0539: CALL 055
.................... output_low(LED3);
053A: BSF 03.5
053B: BCF 05.7
053C: BCF 03.5
053D: BCF 05.7
.................... beep(3000,400);
053E: MOVLW 0B
053F: MOVWF 37
0540: MOVLW B8
0541: MOVWF 36
0542: MOVLW 01
0543: MOVWF 39
0544: MOVLW 90
0545: MOVWF 38
0546: CALL 055
.................... Delay_ms(1000);
0547: MOVLW 04
0548: MOVWF 34
0549: MOVLW FA
054A: MOVWF 37
054B: CALL 073
054C: DECFSZ 34,F
054D: GOTO 549
.................... output_high(LED1); output_high(LED2);
054E: BSF 03.5
054F: BCF 05.4
0550: BCF 03.5
0551: BSF 05.4
0552: BSF 03.5
0553: BCF 05.3
0554: BCF 03.5
0555: BSF 05.3
.................... output_high(LED3); output_high(LED4);
0556: BSF 03.5
0557: BCF 05.7
0558: BCF 03.5
0559: BSF 05.7
055A: BSF 03.5
055B: BCF 05.6
055C: BCF 03.5
055D: BSF 05.6
.................... enable_interrupts(GLOBAL);
055E: MOVLW C0
055F: IORWF 0B,F
.................... }
.................... };
....................
.................... if (L==line) // kdyz jsou obe cidla mimo caru, zatoc na caru
0560: MOVF 2A,W
0561: SUBLW 02
0562: BTFSS 03.2
0563: GOTO 582
.................... {
.................... STOPL;
0564: BSF 03.5
0565: BCF 06.6
0566: BCF 03.5
0567: BCF 06.6
0568: BSF 03.5
0569: BCF 06.7
056A: BCF 03.5
056B: BCF 06.7
.................... GO(R, F, speed);
056C: MOVF 01,W
056D: SUBWF 2B,W
056E: BTFSS 03.0
056F: GOTO 579
0570: BSF 03.5
0571: BCF 06.5
0572: BCF 03.5
0573: BCF 06.5
0574: BSF 03.5
0575: BCF 06.4
0576: BCF 03.5
0577: BSF 06.4
0578: GOTO 581
0579: BSF 03.5
057A: BCF 06.4
057B: BCF 03.5
057C: BCF 06.4
057D: BSF 03.5
057E: BCF 06.5
057F: BCF 03.5
0580: BCF 06.5
.................... }
.................... else
0581: GOTO 59F
.................... {
.................... STOPR;
0582: BSF 03.5
0583: BCF 06.4
0584: BCF 03.5
0585: BCF 06.4
0586: BSF 03.5
0587: BCF 06.5
0588: BCF 03.5
0589: BCF 06.5
.................... GO(L, F, speed);
058A: MOVF 01,W
058B: SUBWF 2B,W
058C: BTFSS 03.0
058D: GOTO 597
058E: BSF 03.5
058F: BCF 06.7
0590: BCF 03.5
0591: BCF 06.7
0592: BSF 03.5
0593: BCF 06.6
0594: BCF 03.5
0595: BSF 06.6
0596: GOTO 59F
0597: BSF 03.5
0598: BCF 06.6
0599: BCF 03.5
059A: BCF 06.6
059B: BSF 03.5
059C: BCF 06.7
059D: BCF 03.5
059E: BCF 06.7
.................... }
....................
.................... } // while(true)
059F: GOTO 3CB
.................... }
....................
....................
05A0: SLEEP
 
Configuration Fuses:
Word 1: 3F38 NOWDT NOPUT MCLR NOBROWNOUT NOLVP NOCPD NOWRT NODEBUG CCPB0 NOPROTECT INTRC_IO
Word 2: 3FFC NOFCMEN NOIESO
/roboti/istrobot/merkur/PIC16F88/MerkurU/tank.PJT
0,0 → 1,40
[PROJECT]
Target=tank.HEX
Development_Mode=
Processor=0x688F
ToolSuite=CCS
 
[Directories]
Include=C:\Program Files\PICC\devices\;C:\Program Files\PICC\drivers\;C:\library\CCS;
Library=
LinkerScript=
 
[Target Data]
FileList=tank.c;
BuildTool=C-COMPILER
OptionString=+FM
AdditionalOptionString=
BuildRequired=1
 
[tank.c]
Type=4
Path=
FileList=
BuildTool=
OptionString=
AdditionalOptionString=
 
[mru-list]
1=tank.c
 
[Windows]
0=0000 tank.c 0 0 796 451 3 0
 
[Opened Files]
1=D:\KAKLIK\programy\PIC_C\roboti\merkur\PIC16F88\MerkurU\tank.c
2=C:\Program Files\PICC\devices\16F88.h
3=D:\KAKLIK\programy\PIC_C\roboti\merkur\PIC16F88\MerkurU\tank.h
4=
5=
6=
7=
/roboti/istrobot/merkur/PIC16F88/MerkurU/tank.SYM
0,0 → 1,71
015-016 CCP_1
015 CCP_1_LOW
016 CCP_1_HIGH
020 @INTERRUPT_AREA
021 @INTERRUPT_AREA
022 @INTERRUPT_AREA
023 @INTERRUPT_AREA
024 @INTERRUPT_AREA
025 @INTERRUPT_AREA
026 @INTERRUPT_AREA
027 @INTERRUPT_AREA
028 @INTERRUPT_AREA
029 sensors
02A line
02B speed
02C last
02D rovinka
02E cirkus
02F.0 BW
030-031 main.n
032-033 main.i
034-035 diagnostika.n
034-035 OtocSe.n
034 main.@SCRATCH
035 main.@SCRATCH
036-037 beep.period
036 diagnostika.@SCRATCH
036 OtocSe.@SCRATCH
037 @delay_ms1.P1
037 OtocSe.@SCRATCH
038-039 beep.length
03A-03B beep.nn
03C @delay_us1.P1
077 @SCRATCH
078 @SCRATCH
078 _RETURN_
079 @SCRATCH
07A @SCRATCH
07B @SCRATCH
09C.6 C1OUT
09C.7 C2OUT
 
0073 @delay_ms1
0042 @delay_us1
0037 TIMER2_isr
0055 beep
0088 diagnostika
01F8 OtocSe
02D1 main
02D1 @cinit
 
Project Files:
D:\KAKLIK\programy\PIC_C\roboti\merkur\PIC16F88\MerkurU\tank.c
D:\KAKLIK\programy\PIC_C\roboti\merkur\PIC16F88\MerkurU\tank.h
C:\Program Files\PICC\devices\16F88.h
 
Compiler Settings:
Processor: PIC16F88
Pointer Size: 8
ADC Range: 0-255
Opt Level: 9
Short,Int,Long: 1,8,16
 
Output Files:
Errors: D:\KAKLIK\programy\PIC_C\roboti\merkur\PIC16F88\MerkurU\tank.err
INHX8: D:\KAKLIK\programy\PIC_C\roboti\merkur\PIC16F88\MerkurU\tank.HEX
Symbols: D:\KAKLIK\programy\PIC_C\roboti\merkur\PIC16F88\MerkurU\tank.SYM
List: D:\KAKLIK\programy\PIC_C\roboti\merkur\PIC16F88\MerkurU\tank.LST
Debug/COFF: D:\KAKLIK\programy\PIC_C\roboti\merkur\PIC16F88\MerkurU\tank.cof
Call Tree: D:\KAKLIK\programy\PIC_C\roboti\merkur\PIC16F88\MerkurU\tank.tre
Statistics: D:\KAKLIK\programy\PIC_C\roboti\merkur\PIC16F88\MerkurU\tank.sta
/roboti/istrobot/merkur/PIC16F88/MerkurU/tank.c
0,0 → 1,268
// Program pro predvadeni schopnosti robota Merkur
//------------------------------------------------
 
#include "tank.h"
 
unsigned int8 sensors; // pomocna promenna pro cteni cidel na caru
unsigned int8 line; // na ktere strane byla detekovana cara
unsigned int8 speed; // rychlost zataceni
unsigned int8 last; // kde byla cara, kdyz byly minule cidla mimo
unsigned int8 rovinka; // pocitadlo pro zjisteni rovneho useku
int cirkus; // pocitadlo, po kolika akcich se ma delat cirkus
int1 BW; // urcuje, jestli je cara cerno/bila nebo
// bilo/cerna (true = bila cara, cerny podklad)
 
// Konstanty pro dynamiku pohybu
#define T_DIRA 120 // po jakem case zataceni se detekuje dira
#define FW_POMALU 170 // trochu mimo caru vnitrni pas
#define FW_ZATACKA 200 // rychlost vnejsiho kola pri zataceni
#define FW_STREDNE 190 // trochu mimo caru vnejsi pas
#define COUVANI 750 // couvnuti zpet na caru, po detekci diry
#define MAX_ROVINKA (255-FW_STREDNE)
#define TRESHOLD 15 // rozhodovaci uroven komparatoru, 0xF = 0.75*Vdd
#define BUMPER_TRESHOLD 128 // rozhodovaci uroven cidla na prekazku
 
//motory //Napred vypnout potom zapnout!
#define FR output_low(PIN_B5); output_high(PIN_B4) // Vpred
#define FL output_low(PIN_B7); output_high(PIN_B6)
#define BR output_low(PIN_B4); output_high(PIN_B5) // Vzad
#define BL output_low(PIN_B6); output_high(PIN_B7)
#define STOPR output_low(PIN_B4);output_low(PIN_B5) // Zastav
#define STOPL output_low(PIN_B6);output_low(PIN_B7)
 
#define L 0b10 // left
#define R 0b01 // right
#define S 0b11 // straight
 
//cidla
#define RSENSOR (BW != C2OUT) // Senzory na caru
#define LSENSOR (BW != C1OUT)
#define BUMPER sAN2 // Senzor na cihlu
 
#define DIAG_SERVO PIN_B3 // Propojka pro diagnosticky mod
#define DIAG_SENSORS PIN_B2 // Propojka pro diagnosticky mod
#define BARVY PIN_B1 // Propojka pro nastaveni barvy cary
 
#define SPEAKER PIN_B0 // vystup pro pipak
 
#define LED1 PIN_A4 // LEDky
#define LED2 PIN_A3
#define LED3 PIN_A7
#define LED4 PIN_A6
 
// makro pro PWM
#define GO(motor, direction, power) if(get_timer0()<=power) \
{direction##motor;} else {stop##motor;}
 
#int_TIMER2
void TIMER2_isr() // obsluha zrychlovani
{
if (speed<255) speed++;
if (rovinka<MAX_ROVINKA) rovinka++;
}
 
// Primitivni Pipani
void beep(unsigned int16 period, unsigned int16 length)
{
unsigned int16 nn;
 
for(nn=length; nn>0; nn--)
{
output_high(SPEAKER);
delay_us(period);
output_low(SPEAKER);
delay_us(period);
}
}
/******************************************************************************/
void diagnostika()
{
unsigned int16 n;
 
while (input(DIAG_SERVO)) // Propojka, ktera spousti diagnostiku
{
for (n=500; n<800; n+=100)
{
beep(n,n); //beep UP
};
Delay_ms(1000);
//zastav vse
STOPL; STOPR;
//pravy pas
FR; Delay_ms(1000); STOPR; Delay_ms(1000);
BR; Delay_ms(1000); STOPR; Delay_ms(1000);
Beep(880,100); Delay_ms(1000);
//levy pas
FL; Delay_ms(1000); STOPL; Delay_ms(1000);
BL; Delay_ms(1000); STOPL; Delay_ms(1000);
Beep(880,100); Delay_ms(1000);
//oba pasy
FL; FR; Delay_ms(1000); STOPL; STOPR; Delay_ms(1000);
BL; BR; Delay_ms(1000); STOPL; STOPR; Delay_ms(1000);
};
while (input(DIAG_SENSORS)) // spusteni diagnostiky cidel
{
if (RSENSOR) beep(1000,200);
Delay_ms(200);
if (LSENSOR) beep(2000,300);
Delay_ms(200);
if ((read_adc(ADC_READ_ONLY)<BUMPER_TRESHOLD)) beep(3000,400);
Delay_ms(200);
};
}
///////////////////////////////////////////////////////////////////////////////
void OtocSe() // otoci se zpet, kdyz je prekazka
{
unsigned int16 n;
 
BL; BR; // cukni zpatky
Delay_ms(200);
STOPR;STOPL;
beep(800,400);
beep(2000,1000);
output_low(LED4);
beep(900,400);
output_low(LED1);
 
BR; FL; Delay_ms(100); // otoc se 30° do prava
STOPL; STOPR;
beep(1000,1000);
output_low(LED3);
 
BR; FL;
for(n=40000;n>0;n--) // toc se, dokud nenarazis na caru
{
line = RSENSOR; // cteni senzoru na caru
line |= LSENSOR << 1;
if (line!=0) break;
}
STOPR; STOPL;
output_high(LED1); output_high(LED3); output_high(LED4);
 
line=L; // caru jsme prejeli, tak je vlevo
cirkus=0;
}
 
 
void main()
{
unsigned int16 n; // pro FOR
unsigned int16 i;
 
STOPL; STOPR; // prepne vystupy na ovladani motoru na output a zastavi
 
setup_oscillator(OSC_4MHZ|OSC_INTRC); // 4 MHz interni RC oscilator
 
port_b_pullups(TRUE); // pullups pro piano na diagnostiku
setup_spi(FALSE);
setup_timer_0(RTCC_INTERNAL|RTCC_DIV_1); // Casovac pro PWM
 
setup_timer_2(T2_DIV_BY_4,255,10); // Casovac pro regulaci
// preruseni kazdych 10ms
setup_adc_ports(BUMPER|VSS_VDD); // nastaveni A/D prevodniku pro naraznik
setup_adc(ADC_CLOCK_INTERNAL);
set_adc_channel(2);
setup_timer_1(T1_INTERNAL|T1_DIV_BY_1); // Casovac pro naraznik
setup_ccp1(CCP_COMPARE_RESET_TIMER);
CCP_1=(2^10)-1; // prevod kazdou 1ms
 
output_low(LED1); output_low(LED2); output_low(LED3); output_low(LED4);
 
setup_comparator(A0_VR_A1_VR); // inicializace komparatoru pro cidla cary
setup_vref(VREF_HIGH|TRESHOLD); // 32 kroku od 0.25 do 0.75 Vdd
 
Beep(1000,200); //double beep
Delay_ms(50);
Beep(1000,200);
Delay_ms(1000); // 1s
 
// povoleni rizeni rychlosti zataceni pres preruseni
enable_interrupts(INT_TIMER2);
enable_interrupts(GLOBAL);
 
/*---------------------------------------------------------------------------*/
sensors=S;
line=S;
last=S;
cirkus=0;
// movement=S;
speed=FW_POMALU;
 
BW=input(BARVY); // Jaka ma byt barva cary?
diagnostika(); // Zkus, jestli nekdo nechce, diagnostiku
Delay_ms(500);
 
output_high(LED1); Beep(1000,200); Delay_ms(500);
output_high(LED2); Beep(1000,200); Delay_ms(500);
output_high(LED3); Beep(1000,200); Delay_ms(500);
output_high(LED4); Beep(1000,200); Delay_ms(500);
 
while(true) // hlavni smycka (jizda podle cary)
{
sensors = RSENSOR; // cteni senzoru na caru
sensors |= LSENSOR << 1;
 
if (read_adc(ADC_READ_ONLY)<BUMPER_TRESHOLD) OtocSe();
 
switch (sensors) // zatacej podle toho, kde vidis caru
{
case S: // rovne
GO(L, F, FW_STREDNE+rovinka); GO(R, F, FW_STREDNE+rovinka);
continue;
case L: // trochu vlevo
GO(L, F, FW_POMALU+rovinka); GO(R, F, FW_STREDNE+rovinka);
line=L;
continue;
case R: // trochu vpravo
GO(R, F, FW_POMALU+rovinka); GO(L, F, FW_STREDNE+rovinka);
line=R;
continue;
default: // kdyz jsou obe cidla mimo caru, tak pokracuj dal
};
rovinka=0;
 
if (last!=line) // pokud si prejel caru z jedne strany na druhou stranu,
// tak zabrzdi
{
output_bit(LED1, !input(LED1));
last=line;
speed=FW_ZATACKA;
cirkus++;
if (cirkus>8)
{
STOPL; STOPR;
cirkus=0;
disable_interrupts(GLOBAL);
beep(1000,400);
for(n=3000; n>3950; n--) beep(n,10);
output_low(LED1);
beep(2000,200);
beep(900,400);
for(n=2950; n<3000; n++) beep(n,10);
output_low(LED2);
output_high(LED1);
beep(4000,400);
beep(1000,100);
output_low(LED3);
beep(3000,400);
Delay_ms(1000);
output_high(LED1); output_high(LED2);
output_high(LED3); output_high(LED4);
enable_interrupts(GLOBAL);
}
};
 
if (L==line) // kdyz jsou obe cidla mimo caru, zatoc na caru
{
STOPL;
GO(R, F, speed);
}
else
{
STOPR;
GO(L, F, speed);
}
 
} // while(true)
}
 
/roboti/istrobot/merkur/PIC16F88/MerkurU/tank.cof
Cannot display: file marked as a binary type.
svn:mime-type = application/octet-stream
Property changes:
Added: svn:mime-type
+application/octet-stream
\ No newline at end of property
/roboti/istrobot/merkur/PIC16F88/MerkurU/tank.err
0,0 → 1,0
No Errors
/roboti/istrobot/merkur/PIC16F88/MerkurU/tank.h
0,0 → 1,5
#include <16F88.h>
#device adc=8
#fuses NOWDT,INTRC_IO, NOPUT, MCLR, NOBROWNOUT, NOLVP, NOCPD, NOWRT, NODEBUG, NOPROTECT, NOFCMEN, NOIESO
#use delay(clock=4000000)
 
/roboti/istrobot/merkur/PIC16F88/MerkurU/tank.sta
0,0 → 1,35
 
ROM used: 1441 (35%)
1441 (35%) including unused fragments
 
3 Average locations per line
5 Average locations per statement
 
RAM used: 27 (15%) at main() level
34 (19%) worst case
 
Lines Stmts % Files
----- ----- --- -----
269 293 100 D:\KAKLIK\programy\PIC_C\roboti\merkur\PIC16F88\MerkurU\tank.c
6 0 0 D:\KAKLIK\programy\PIC_C\roboti\merkur\PIC16F88\MerkurU\tank.h
275 0 0 C:\Program Files\PICC\devices\16F88.h
----- -----
1100 586 Total
 
Page ROM % RAM Functions:
---- --- --- --- ----------
0 21 1 1 @delay_ms1
0 19 1 1 @delay_us1
0 11 1 0 TIMER2_isr
0 30 2 6 beep
0 368 26 3 diagnostika
0 217 15 4 OtocSe
0 720 50 6 main
 
Segment Used Free
--------- ---- ----
00000-00003 4 0
00004-00036 51 0
00037-007FF 1386 607
00800-00FFF 0 2048
 
/roboti/istrobot/merkur/PIC16F88/MerkurU/tank.tre
0,0 → 1,106
ÀÄtank
ÃÄmain 0/720 Ram=6
³ ÃÄ??0??
³ ÃÄbeep 0/30 Ram=6
³ ³ ÃÄ@delay_us1 0/19 Ram=1
³ ³ ÀÄ@delay_us1 0/19 Ram=1
³ ÃÄ@delay_ms1 0/21 Ram=1
³ ÃÄbeep 0/30 Ram=6
³ ³ ÃÄ@delay_us1 0/19 Ram=1
³ ³ ÀÄ@delay_us1 0/19 Ram=1
³ ÃÄ@delay_ms1 0/21 Ram=1
³ ÃÄdiagnostika 0/368 Ram=3
³ ³ ÃÄbeep 0/30 Ram=6
³ ³ ³ ÃÄ@delay_us1 0/19 Ram=1
³ ³ ³ ÀÄ@delay_us1 0/19 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄbeep 0/30 Ram=6
³ ³ ³ ÃÄ@delay_us1 0/19 Ram=1
³ ³ ³ ÀÄ@delay_us1 0/19 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄbeep 0/30 Ram=6
³ ³ ³ ÃÄ@delay_us1 0/19 Ram=1
³ ³ ³ ÀÄ@delay_us1 0/19 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄbeep 0/30 Ram=6
³ ³ ³ ÃÄ@delay_us1 0/19 Ram=1
³ ³ ³ ÀÄ@delay_us1 0/19 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄbeep 0/30 Ram=6
³ ³ ³ ÃÄ@delay_us1 0/19 Ram=1
³ ³ ³ ÀÄ@delay_us1 0/19 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄbeep 0/30 Ram=6
³ ³ ³ ÃÄ@delay_us1 0/19 Ram=1
³ ³ ³ ÀÄ@delay_us1 0/19 Ram=1
³ ³ ÀÄ@delay_ms1 0/21 Ram=1
³ ÃÄ@delay_ms1 0/21 Ram=1
³ ÃÄbeep 0/30 Ram=6
³ ³ ÃÄ@delay_us1 0/19 Ram=1
³ ³ ÀÄ@delay_us1 0/19 Ram=1
³ ÃÄ@delay_ms1 0/21 Ram=1
³ ÃÄbeep 0/30 Ram=6
³ ³ ÃÄ@delay_us1 0/19 Ram=1
³ ³ ÀÄ@delay_us1 0/19 Ram=1
³ ÃÄ@delay_ms1 0/21 Ram=1
³ ÃÄbeep 0/30 Ram=6
³ ³ ÃÄ@delay_us1 0/19 Ram=1
³ ³ ÀÄ@delay_us1 0/19 Ram=1
³ ÃÄ@delay_ms1 0/21 Ram=1
³ ÃÄbeep 0/30 Ram=6
³ ³ ÃÄ@delay_us1 0/19 Ram=1
³ ³ ÀÄ@delay_us1 0/19 Ram=1
³ ÃÄ@delay_ms1 0/21 Ram=1
³ ÃÄOtocSe 0/217 Ram=4
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄbeep 0/30 Ram=6
³ ³ ³ ÃÄ@delay_us1 0/19 Ram=1
³ ³ ³ ÀÄ@delay_us1 0/19 Ram=1
³ ³ ÃÄbeep 0/30 Ram=6
³ ³ ³ ÃÄ@delay_us1 0/19 Ram=1
³ ³ ³ ÀÄ@delay_us1 0/19 Ram=1
³ ³ ÃÄbeep 0/30 Ram=6
³ ³ ³ ÃÄ@delay_us1 0/19 Ram=1
³ ³ ³ ÀÄ@delay_us1 0/19 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÀÄbeep 0/30 Ram=6
³ ³ ÃÄ@delay_us1 0/19 Ram=1
³ ³ ÀÄ@delay_us1 0/19 Ram=1
³ ÃÄbeep 0/30 Ram=6
³ ³ ÃÄ@delay_us1 0/19 Ram=1
³ ³ ÀÄ@delay_us1 0/19 Ram=1
³ ÃÄbeep 0/30 Ram=6
³ ³ ÃÄ@delay_us1 0/19 Ram=1
³ ³ ÀÄ@delay_us1 0/19 Ram=1
³ ÃÄbeep 0/30 Ram=6
³ ³ ÃÄ@delay_us1 0/19 Ram=1
³ ³ ÀÄ@delay_us1 0/19 Ram=1
³ ÃÄbeep 0/30 Ram=6
³ ³ ÃÄ@delay_us1 0/19 Ram=1
³ ³ ÀÄ@delay_us1 0/19 Ram=1
³ ÃÄbeep 0/30 Ram=6
³ ³ ÃÄ@delay_us1 0/19 Ram=1
³ ³ ÀÄ@delay_us1 0/19 Ram=1
³ ÃÄbeep 0/30 Ram=6
³ ³ ÃÄ@delay_us1 0/19 Ram=1
³ ³ ÀÄ@delay_us1 0/19 Ram=1
³ ÃÄbeep 0/30 Ram=6
³ ³ ÃÄ@delay_us1 0/19 Ram=1
³ ³ ÀÄ@delay_us1 0/19 Ram=1
³ ÃÄbeep 0/30 Ram=6
³ ³ ÃÄ@delay_us1 0/19 Ram=1
³ ³ ÀÄ@delay_us1 0/19 Ram=1
³ ÀÄ@delay_ms1 0/21 Ram=1
ÀÄTIMER2_isr 0/11 Ram=0
/roboti/istrobot/merkur/PIC16F88/turn_L/AX25.c
0,0 → 1,135
#nolist
//#define PTT PIN_A2 // PTT control
//#define TXo PIN_C0 // To the transmitter modulator
#define PERIODAH delay_us(222) // Halfperiod H 222;78/1200 500;430/500
#define TAILH delay_us(78)
#define PERIODAL delay_us(412) // Halfperiod L 412;345/1200 1000;880/500
#define TAILL delay_us(345)
#byte STATUS = 3 // CPUs status register
 
byte SendData[16] = {'A'<<1, 'L'<<1, 'L'<<1, ' '<<1, ' '<<1, ' '<<1, 0x60,
'C'<<1, 'Z'<<1, '0'<<1, 'R'<<1, 'R'<<1, 'R'<<1, 0x61,
0x03, 0xF0};
 
boolean bit;
int fcslo, fcshi; // variabloes for calculating FCS (CRC)
int stuff; // stuff counter for extra 0
int flag_flag; // if it is sending flag (7E)
int fcs_flag; // if it is sending Frame Check Sequence
int i; // for for
 
void flipout() //flips the state of output pin a_1
{
stuff = 0; //since this is a 0, reset the stuff counter
if (bit)
{
bit=FALSE; //if the state of the pin was low, make it high.
}
else
{
bit=TRUE; //if the state of the pin was high make it low
}
}
 
void fcsbit(byte tbyte)
{
#asm
BCF STATUS,0
RRF fcshi,F // rotates the entire 16 bits
RRF fcslo,F // to the right
#endasm
if (((STATUS & 0x01)^(tbyte)) ==0x01)
{
fcshi = fcshi^0x84;
fcslo = fcslo^0x08;
}
}
 
void SendBit ()
{
if (bit)
{
output_high(TXo);
PERIODAH;
output_low(TXo);
PERIODAH;
output_high(TXo);
PERIODAH;
output_low(TXo);
TAILH;
}
else
{
output_high(TXo);
PERIODAL;
output_low(TXo);
TAILL;
};
}
 
void SendByte (byte inbyte)
{
int k, bt;
 
for (k=0;k<8;k++) //do the following for each of the 8 bits in the byte
{
bt = inbyte & 0x01; //strip off the rightmost bit of the byte to be sent (inbyte)
if ((fcs_flag == FALSE) & (flag_flag == FALSE)) fcsbit(bt); //do FCS calc, but only if this
//is not a flag or fcs byte
if (bt == 0)
{
flipout();
} // if this bit is a zero, flip the output state
else
{ //otherwise if it is a 1, do the following:
if (flag_flag == FALSE) stuff++; //increment the count of consequtive 1's
if ((flag_flag == FALSE) & (stuff == 5))
{ //stuff an extra 0, if 5 1's in a row
SendBit();
flipout(); //flip the output state to stuff a 0
}//end of if
}//end of else
// delay_us(850); //introduces a delay that creates 1200 baud
SendBit();
inbyte = inbyte>>1; //go to the next bit in the byte
}//end of for
}//end of SendByte
 
void SendPacket(char *data)
{
bit=FALSE;
 
fcslo=fcshi=0xFF; //The 2 FCS Bytes are initialized to FF
stuff = 0; //The variable stuff counts the number of 1's in a row. When it gets to 5
// it is time to stuff a 0.
 
// output_low(PTT); // Blinking LED
// delay_ms(1000);
// output_high(PTT);
 
flag_flag = TRUE; //The variable flag is true if you are transmitted flags (7E's) false otherwise.
fcs_flag = FALSE; //The variable fcsflag is true if you are transmitting FCS bytes, false otherwise.
 
for(i=0; i<10; i++) SendByte(0x7E); //Sends flag bytes. Adjust length for txdelay
//each flag takes approx 6.7 ms
flag_flag = FALSE; //done sending flags
 
for(i=0; i<16; i++) SendByte(SendData[i]); //send the packet bytes
 
for(i=0; 0 != *data; i++)
{
SendByte(*data); //send the packet bytes
data++;
};
 
fcs_flag = TRUE; //about to send the FCS bytes
fcslo =fcslo^0xff; //must XOR them with FF before sending
fcshi = fcshi^0xff;
SendByte(fcslo); //send the low byte of fcs
SendByte(fcshi); //send the high byte of fcs
fcs_flag = FALSE; //done sending FCS
flag_flag = TRUE; //about to send flags
SendByte(0x7e); // Send a flag to end packet
}
 
#list
/roboti/istrobot/merkur/PIC16F88/turn_L/tank.BAK
0,0 → 1,340
#include "tank.h"
 
#define DEBUG
 
#define TXo PIN_A3 // To the transmitter modulator
#include "AX25.c" // podprogram pro prenos telemetrie
 
unsigned int8 sensors; // pomocna promenna pro cteni cidel na caru
unsigned int8 line; // na ktere strane byla detekovana cara
unsigned int8 speed; // rychlost zataceni
unsigned int8 rovinka; // pocitadlo pro zjisteni rovneho useku
unsigned int8 last; // kde byla cara, kdyz byly minule cidla mimo
unsigned int8 movement; // obsahuje aktualni smer zataceni
unsigned int8 dira; // pocita dobu po kterou je ztracena cara
 
// Konstanty pro dynamiku pohybu
#define T_DIRA 87 // po jakem case zataceni se detekuje dira
#define INC_SPEED 1 // prirustek rychlosti v jednom kroku
#define FW_POMALU 230 // trochu mimo caru vnitrni pas
#define FW_ZATACKA 200 // rychlost vnejsiho kola pri zataceni
#define FW_STREDNE 240 // trochu mimo caru vnejsi pas
#define COUVANI 600 // couvnuti zpet na caru, po detekci diry
#define PRES_DIRU 250
#define MAX_ROVINKA (255-FW_STREDNE)
#define TRESHOLD 10 // rozhodovaci uroven komparatoru, 0xF = 0.75*Vdd
#define BUMPER_TRESHOLD 128
#define CIK_CAK 30000
#define T_CIHLA 50 // perioda detekce cihly
 
//motory //Napred vypnout potom zapnout!
#define FR output_low(PIN_B5); output_high(PIN_B4) // Vpred
#define FL output_low(PIN_B7); output_high(PIN_B6)
#define BR output_low(PIN_B4); output_high(PIN_B5) // Vzad
#define BL output_low(PIN_B6); output_high(PIN_B7)
#define STOPR output_low(PIN_B4);output_low(PIN_B5) // Zastav
#define STOPL output_low(PIN_B6);output_low(PIN_B7)
 
#define L 0b10 // left
#define R 0b01 // right
#define S 0b11 // straight
 
//cidla
#define RSENSOR C2OUT // Senzory na caru
#define LSENSOR C1OUT
#define BUMPER PIN_A4 // Senzor na cihlu
 
#define DIAG_SERVO PIN_B3 // Propojka pro diagnosticky mod
#define DIAG_SENSORS PIN_B2 // Propojka pro diagnosticky mod
 
#DEFINE SOUND_HI PIN_A6 // komplementarni vystupy pro piezo pipak
#DEFINE SOUND_LO PIN_A7
 
char AXstring[40]; // Buffer pro prenos telemetrie
 
// makro pro PWM
#define GO(motor, direction, power) if(get_timer0()<=power) \
{direction##motor;} else {stop##motor;}
 
#int_TIMER2
void TIMER2_isr()
{
if (speed<255) speed+=INC_SPEED;
if (rovinka<MAX_ROVINKA) rovinka++;
if (dira<=T_DIRA) dira++;
}
// Primitivni Pipani
void beep(unsigned int16 period, unsigned int16 length)
{
unsigned int16 nn;
 
for(nn=length; nn>0; nn--)
{
output_high(SOUND_HI);output_low(SOUND_LO);
delay_us(period);
output_high(SOUND_LO);output_low(SOUND_HI);
delay_us(period);
}
}
/******************************************************************************/
void diagnostika()
{
unsigned int16 n;
 
while (input(DIAG_SERVO)) // Propojka, ktera spousti diagnostiku
{
for (n=500; n<800; n+=100)
{
beep(n,n); //beep UP
};
Delay_ms(1000);
//zastav vse
STOPL; STOPR;
//pravy pas
FR; Delay_ms(1000); STOPR; Delay_ms(1000);
BR; Delay_ms(1000); STOPR; Delay_ms(1000);
Beep(880,100); Delay_ms(1000);
//levy pas
FL; Delay_ms(1000); STOPL; Delay_ms(1000);
BL; Delay_ms(1000); STOPL; Delay_ms(1000);
Beep(880,100); Delay_ms(1000);
//oba pasy
FL; FR; Delay_ms(1000); STOPL; STOPR; Delay_ms(1000);
BL; BR; Delay_ms(1000); STOPL; STOPR; Delay_ms(1000);
};
while (input(DIAG_SENSORS))
{
if (RSENSOR) beep(900,500);
if (LSENSOR) beep(800,500);
if ((read_adc(ADC_READ_ONLY)<BUMPER_TRESHOLD)) beep(1000,500);
};
}
///////////////////////////////////////////////////////////////////////////////
void cikcak()
{
unsigned int16 n;
sem1:
n=CIK_CAK;
while (0==RSENSOR||LSENSOR) // zkontroluj caru
{
if (n==CIK_CAK) // zmen smer zataceni
{
n=0;
switch(movement)
{
case L:
FL;BR;
movement=R;
break;
case R:
FR;BL;
movement=L;
break;
case S:
FL;BR;
movement=R;
n=CIK_CAK/2;
break;
}
}
n++;
}
STOPL;STOPR;
line = RSENSOR; // cteni senzoru na caru
line |= LSENSOR << 1;
if (line==0) goto sem1;
// nasli jsme caru
line=S;
}
///////////////////////////////////////////////////////////////////////////////
void objizdka() // objede cihlu
{
unsigned int16 n;
 
BL;BR;Delay_ms(200);
STOPR;STOPL;
beep(900,1000);
// movement=S;
//cikcak();
 
BL; FR; Delay_ms(215); // otoc se 70° do leva
 
FR; FL; Delay_ms(600); // popojed rovne
 
BR; Delay_ms(50); // otoc se 90° do prava
STOPR; FL; Delay_ms(700);
 
FR; FL; Delay_ms(100); // popojed rovne na slepo
for(n=600;n>0;n--) // popojed rovne ale kontroluj caru
{
line = RSENSOR; // cteni senzoru na caru
line |= LSENSOR << 1;
if (line!=0) {Delay_ms(50); break;} // kdyz narazis na caru, za chvili zastav
Delay_ms(1);
}
 
BL; // otoc se 60° do leva
for(n=600;n>0;n--)
{
line = RSENSOR; // cteni senzoru na caru
line |= LSENSOR << 1;
if (line!=0) break;
Delay_ms(1);
}
STOPR; STOPL;
 
movement=R;
cikcak();
dira=0;
}
///////////////////////////////////////////////////////////////////////////////
void prejeddiru() // vyresi diru
{
unsigned int16 n;
unsigned int8 speed_dira;
 
STOPL;STOPR;
speed_dira=speed;
beep(1000,500);
switch (movement) //vrat se zpet na caru
{
case L:
for (n=COUVANI;n>0;n--) {GO(R,B,speed_dira); Delay_ms(1);}
STOPL;STOPR;
break;
case R:
for (n=COUVANI;n>0;n--) {GO(L,B,speed_dira); Delay_ms(1);}
STOPL;STOPR;
break;
case S:
goto sem;
break;
}
beep(800,500);
 
line=0;
FR; BL; Delay_ms(300); // otoc se na caru
while(line==0)
{
line = RSENSOR; // cteni senzoru na caru
line |= LSENSOR << 1;
}
FL;BR; Delay_ms(60);
STOPL; STOPR;
 
FL; BR; Delay_ms(500);
STOPL; STOPR;
 
Delay_ms(1000);
 
FR;FL; //popojed rovne
for(n=PRES_DIRU;n>0;n--)
{
line = RSENSOR; // cteni senzoru na caru
line |= LSENSOR << 1;
if (line!=0) break;
Delay_ms(1);
}
sem:
STOPL; STOPR;
movement=S;
cikcak(); // najdi caru
dira=0;
}
///////////////////////////////////////////////////////////////////////////////
void main()
{
unsigned int16 n; // pro FOR
 
STOPL; STOPR; // prepne vystupy na ovladani motoru na output a zastavi
 
setup_oscillator(OSC_4MHZ|OSC_INTRC); // 4 MHz interni RC oscilator
 
port_b_pullups(TRUE); // pullups pro piano na diagnostiku
setup_spi(FALSE);
setup_timer_0(RTCC_INTERNAL|RTCC_DIV_1); // Casovac pro PWM
 
setup_timer_2(T2_DIV_BY_4,255,10); // Casovac pro regulaci
// preruseni kazdych 10ms
setup_adc_ports(sAN2|VSS_VDD); // nastaveni A/D prevodniku pro naraznik
setup_adc(ADC_CLOCK_INTERNAL);
set_adc_channel(2);
setup_timer_1(T1_INTERNAL|T1_DIV_BY_1); // Casovac pro naraznik
setup_ccp1(CCP_COMPARE_RESET_TIMER);
CCP_1=(2^10)-1; // prevod kazdou 1ms
 
setup_comparator(A0_VR_A1_VR); // inicializace komparatoru pro cidla cary
setup_vref(VREF_HIGH|TRESHOLD); // 32 kroku od 0.25 do 0.75 Vdd
 
Beep(1000,200); //double beep
Delay_ms(50);
Beep(1000,200);
Delay_ms(1000); // 1s
 
// povoleni rizeni rychlosti zataceni pres preruseni
enable_interrupts(INT_TIMER2);
enable_interrupts(GLOBAL);
 
/*---------------------------------------------------------------------------*/
sensors=S;
line=S;
last=S;
movement=S;
speed=FW_POMALU;
 
diagnostika();
// cikcak(); // toc se, abys nasel caru
Delay_ms(500);
Beep(1000,200);
Delay_ms(500);
 
while(true) // hlavni smycka (jizda podle cary)
{
sensors = RSENSOR; // cteni senzoru na caru
sensors |= LSENSOR << 1;
 
if ((read_adc(ADC_READ_ONLY)<BUMPER_TRESHOLD) && (dira<=T_CIHLA)) objizdka();
 
switch (sensors) // zatacej podle toho, kde vidis caru
{
case S: // rovne
FL; FR; // pokud se jede dlouho rovne, tak pridej
dira=0;
movement=S;
continue;
case L: // trochu vlevo
GO(L, F, FW_POMALU+rovinka); GO(R, F, FW_STREDNE+rovinka);
line=L;
dira=0;
movement=L;
continue;
case R: // trochu vpravo
GO(R, F, FW_POMALU+rovinka); GO(L, F, FW_STREDNE+rovinka);
line=R;
dira=0;
movement=R;
continue;
default: // kdyz jsou obe cidla mimo caru, tak pokracuj dal
}
rovinka=0;
if (dira>=T_DIRA) prejeddiru();
if (last!=line) // pokud si prejel caru z jedne strany na druhou stranu, tak zabrzdi
{
last=line;
speed=FW_ZATACKA;
}
if (L==line) // kdyz jsou obe cidla mimo caru, zatoc na caru
{
STOPL;
GO(R, F, speed);
movement=L;
}
else
{
STOPR;
GO(L, F, speed);
movement=R;
}
} // while(true)
}
 
/roboti/istrobot/merkur/PIC16F88/turn_L/tank.HEX
0,0 → 1,217
:1000000000308A00E82C0000FF00030E8301A100ED
:100010007F08A0000A08A8008A01A00E0408A20018
:100020007708A3007808A4007908A5007A08A6003C
:100030007B08A700831383128C308400801C222845
:100040008C183528220884002308F7002408F800BB
:100050002508F9002608FA002708FB0028088A006E
:10006000210E8300FF0E7F0E09008A113728420FF0
:100070003A283C280130C20743080E3C0318C30A43
:100080004608573C0318C60A8C108A1122281230E1
:100090008316A202031C5A28A2308400FC3080057B
:1000A0000310800C800C000803195A2858280000FF
:1000B000800B5728831200347D088316A1007C082A
:1000C000A000A008031D6728A108031986280513AE
:1000D00083120517831685138312851374088316FC
:1000E000A200831247208316851383128517831677
:1000F00005138312051374088316A2008312472088
:10010000831620080319A103A00361288312003479
:1001100075308400000803199C280130F800F701AD
:10012000F70B9028F80B8F284A30F700F70B96282A
:1001300000000000800B8D28003483168615831282
:10014000861DC8290130F200F430F1007208033C2A
:10015000031CBE28031DB02871081F3C031CBE28C9
:100160007208F5007108F4007208FD007108FC00C7
:100170005C206430F1070318F20AA6280430F3006B
:10018000FA30F5008820F30BC0288316061383127B
:1001900006138316861383128613831606128312A0
:1001A0000612831686128312861283168612831213
:1001B000861283160612831206160430F300FA30F4
:1001C000F5008820F30BDF2883160612831206122F
:1001D00083168612831286120430F300FA30F5007B
:1001E0008820F30BEE28831606128312061283165C
:1001F0008612831286160430F300FA30F500882048
:10020000F30BFD288316061283120612831686123C
:10021000831286120430F300FA30F5008820F30BC5
:100220000C290330F5007030F400FD016430FC004F
:100230005C200430F300FA30F5008820F30B1B2912
:1002400083168613831286138316061383120617EA
:100250000430F300FA30F5008820F30B2A298316C6
:100260000613831206138316861383128613043033
:10027000F300FA30F5008820F30B392983160613B2
:100280008312061383168613831286170430F30035
:10029000FA30F5008820F30B4829831606138312E1
:1002A000061383168613831286130430F300FA3084
:1002B000F5008820F30B57290330F5007030F40067
:1002C000FD016430FC005C200430F300FA30F500DE
:1002D0008820F30B662983168613831286138316F0
:1002E000061383120617831686128312861283164C
:1002F0000612831206160430F300FA30F500882047
:10030000F30B7D29831606138312061383168613B7
:100310008312861383160612831206128316861220
:10032000831286120430F300FA30F5008820F30BB4
:1003300094298316061383120613831686138312D9
:1003400086178316061283120612831686128312EC
:1003500086160430F300FA30F5008820F30BAB2941
:1003600083160613831206138316861383128613CD
:1003700083160612831206128316861283128612C1
:100380000430F300FA30F5008820F30BC2299D28D1
:10039000831606158312061DFB2983169C1FDB2975
:1003A0000330F5008430F4000130FD00F430FC002F
:1003B00083125C2083161C1FE8290330F5002030CF
:1003C000F4000130FD00F430FC0083125C20831641
:1003D00083121F1DED298316E8291E087F3C031C8C
:1003E000FA290330F500E830F4000130FD00F43064
:1003F000FC005C20C8298A11962D7530F50030303C
:10040000F400003083169C1B0130003A03190A2ABD
:100410001C1F642A7408303C031D5E2A7508753C55
:10042000031D5E2AF501F40183124508023A0319FF
:10043000202A033A0319332A023A0319462A5D2A6D
:1004400083168613831286138316061383120617E8
:1004500083160612831206128316861283128616DC
:100460000130C5005D2A8316861283128612831618
:1004700006128312061683160613831206138316BA
:100480008613831286170230C5005D2A83168613F1
:100490008312861383160613831206178316061219
:1004A0008312061283168612831286160130C50047
:1004B0003A30F5009830F4005D2A8316F40A0319E7
:1004C000F50A8312012A8316061383120613831674
:1004D000861383128613831606128312061283165E
:1004E000861283128612C10183169C1F7A2A8312F8
:1004F000C10A831600301C1B0130F7000310F70DF2
:1005000077088312C104C1080319FD290330C10013
:100510000034831606138312061383168613831280
:10052000861783160612831206128316861283120A
:100530008616C830F500882083160612831206122C
:1005400083168612831286128316061383120613ED
:1005500083168613831286130330F5008430F4006B
:100560000330FD00E830FC005C2083160613831284
:100570000613831686138312861783168612831238
:1005800086128316061283120616D730F5008820CD
:10059000831686128312861283160612831206169B
:1005A0008316861383128613831606138312061787
:1005B0000330F300C830F5008820F30BDA2A8316E5
:1005C00006128312061283168612831286163230A2
:1005D000F5008820831606128312061283168612EF
:1005E00083128612831686138312861383160613CC
:1005F000831206170330F300C830F5008820F30B90
:10060000FC2A831686128312861283160612831220
:100610000616831686138312861383160613831217
:1006200006176430F50088200230F2005830F100DF
:10063000F108031D1E2BF20803193D2BC10183167F
:100640009C1F252B8312C10A831600301C1B01300E
:10065000F7000310F70D77088312C104C1080319CE
:10066000352B3230F50088203D2B0130F5008820F5
:1006700071080319F203F103182B83160613831272
:10068000061383168613831286170230F200583041
:10069000F100F108031D4F2BF20803196A2BC10169
:1006A00083169C1F562B8312C10A831600301C1B15
:1006B0000130F7000310F70D77088312C104C10859
:1006C000031D6A2B0130F500882071080319F2031D
:1006D000F103492B83160612831206128316861223
:1006E000831286128316061383120613831686134B
:1006F000831286130130C500FD21C6018A11C62D63
:100700008316061383120613831686138312861329
:10071000831606128312061283168612831286121D
:100720004208F3000330F500E830F4000130FD002A
:10073000F430FC005C204508023A0319A62B033A6A
:100740000319DE2B023A0319162C182C0230F20082
:100750005830F100F108031DB02BF2080319CD2B1E
:1007600001087302031CBD2B8316061283120612A6
:100770008316861283128616C52B831606128312E1
:10078000061283168612831286120130F500882025
:1007900071080319F203F103AA2B831606138312BF
:1007A000061383168613831286138316061283128A
:1007B00006128316861283128612182C0230F2005B
:1007C0005830F100F108031DE82BF2080319052C3D
:1007D00001087302031CF52B8316061383120613FC
:1007E0008316861383128617FD2B83160613831236
:1007F000061383168613831286130130F5008820B2
:1008000071080319F203F103E22B83160613831216
:100810000613831686138312861383160612831219
:1008200006128316861283128612182CD22C182CCC
:100830000330F5002030F4000130FD00F430FC00FE
:100840005C20C1018316861283128612831606125B
:100850008312061683160613831206138316861355
:10086000831286170230F4009630F5008820F40BCE
:10087000342CC108031D4D2CC10183169C1F432C31
:100880008312C10A831600301C1B0130F7000310CD
:10089000F70D77088312C104392C8316861383124F
:1008A0008613831606138312061783160612831205
:1008B000061283168612831286163C30F5008820B5
:1008C0008316061383120613831686138312861368
:1008D000831606128312061283168612831286125C
:1008E0008316861383128613831606138312061744
:1008F0008316061283120612831686128312861638
:100900000230F400FA30F5008820F40B822C8316B4
:100910000613831206138316861383128613831617
:100920000612831206128316861283128612043070
:10093000F400FA30F5008820F40B992C8316861207
:1009400083128612831606128312061683168613E6
:10095000831286138316061383120617F201FA30E8
:10096000F100F108031DB72CF2080319D22CC101C4
:1009700083169C1FBE2C8312C10A831600301C1BD9
:100980000130F7000310F70D77088312C104C10886
:10099000031DD22C0130F500882071080319F203E1
:1009A000F103B12C831606138312061383168613E4
:1009B000831286138316061283120612831686127A
:1009C000831286120330C500FD21C6018A115C2EF8
:1009D00084011F30830583161F129F121B08803964
:1009E0009B0007309C001C0883120D136030831697
:1009F0008F0082308312A9009830AA00AB004030EB
:100A0000AC00AD00AE006030AF008630B000B43056
:100A1000B1006030B200A430B300B400B500613062
:100A2000B6000330B700F030B80083160613831207
:100A300006138316861383128613831606128312F7
:100A400006128316861283128612623083168F0076
:100A50008113831294128316061186140612003035
:100A600083129400831694000108C7390838810066
:100A70004830F800053883129200FF308316920048
:100A80001F129F121B08803904389B001F1383120A
:100A90001F179F1783169F1383121F141030F8001F
:100AA0001F08C73978049F0085309000831686158B
:100AB0000B308312970096010730950002308316A1
:100AC0009C000508033885000330F700F70B662DFE
:100AD0001C0883120D138A3083169D000330F50025
:100AE000E830F400FD01C830FC0083125C20323095
:100AF000F50088200330F500E830F400FD01C8302F
:100B0000FC005C200430F100FA30F5008820F10B85
:100B1000842D83168C14C03083128B040330C000E4
:100B2000C100C400C500E630C2009D280230F100BB
:100B3000FA30F5008820F10B982D0330F500E830ED
:100B4000F400FD01C830FC005C200230F100FA30F6
:100B5000F5008820F10BA72DC00183169C1FB32D33
:100B60008312C00A831600301C1B0130F7000310EB
:100B7000F70D77088312C0041F19BC2D1E087F3C97
:100B8000031CC62D4608323C0318892A4008033A44
:100B90000319D12D013A0319E52D033A03191E2E2D
:100BA000572E831686138312861383160613831219
:100BB0000617831686128312861283160612831274
:100BC0000616C6010330C500AC2D0108F100E63061
:100BD000430771020319EE2D0318F72D83168613B0
:100BE000831286138316061383120617FF2D8316AE
:100BF00006138312061383168613831286130108C5
:100C0000F100F030430771020319082E0318112E6A
:100C10008316861283128612831606128312061614
:100C2000192E831606128312061283168612831259
:100C300086120230C100C601C500AC2D0108F100CA
:100C4000E630430771020319272E0318302E83164E
:100C50008612831286128316061283120616382E07
:100C600083160612831206128316861283128612C8
:100C70000108F100F030430771020319412E0318F7
:100C80004A2E831686138312861383160613831245
:100C90000617522E83160613831206138316861325
:100CA000831286130130C100C601C500AC2DC301FB
:100CB0004608563C031C802B410844020319642E4D
:100CC0004108C400C830C2004108023C031D882E00
:100CD0008316061383120613831686138312861354
:100CE00001084202031C7D2E83168612831286128F
:100CF0008316061283120616852E83160612831299
:100D0000061283168612831286120230C500A72EA1
:100D10008316061283120612831686128312861217
:100D200001084202031C9D2E83168613831286132C
:100D30008316061383120617A52E83160613831235
:100D4000061383168613831286130130C500AC2D5B
:020D500063003E
:04400E00383FFC3FFC
:00000001FF
;PIC16F88
/roboti/istrobot/merkur/PIC16F88/turn_L/tank.LST
0,0 → 1,2051
CCS PCM C Compiler, Version 3.221, 27853 26-IV-05 21:32
 
Filename: D:\KAKLIK\programy\PIC_C\roboti\merkur\PIC16F88\turn_L\tank.LST
 
ROM used: 1705 words (42%)
Largest free fragment is 2048
RAM used: 87 (50%) at main() level
98 (56%) worst case
Stack: 4 worst case (3 in main + 1 for interrupts)
 
*
0000: MOVLW 00
0001: MOVWF 0A
0002: GOTO 4E8
0003: NOP
0004: MOVWF 7F
0005: SWAPF 03,W
0006: CLRF 03
0007: MOVWF 21
0008: MOVF 7F,W
0009: MOVWF 20
000A: MOVF 0A,W
000B: MOVWF 28
000C: CLRF 0A
000D: SWAPF 20,F
000E: MOVF 04,W
000F: MOVWF 22
0010: MOVF 77,W
0011: MOVWF 23
0012: MOVF 78,W
0013: MOVWF 24
0014: MOVF 79,W
0015: MOVWF 25
0016: MOVF 7A,W
0017: MOVWF 26
0018: MOVF 7B,W
0019: MOVWF 27
001A: BCF 03.7
001B: BCF 03.5
001C: MOVLW 8C
001D: MOVWF 04
001E: BTFSS 00.1
001F: GOTO 022
0020: BTFSC 0C.1
0021: GOTO 035
0022: MOVF 22,W
0023: MOVWF 04
0024: MOVF 23,W
0025: MOVWF 77
0026: MOVF 24,W
0027: MOVWF 78
0028: MOVF 25,W
0029: MOVWF 79
002A: MOVF 26,W
002B: MOVWF 7A
002C: MOVF 27,W
002D: MOVWF 7B
002E: MOVF 28,W
002F: MOVWF 0A
0030: SWAPF 21,W
0031: MOVWF 03
0032: SWAPF 7F,F
0033: SWAPF 7F,W
0034: RETFIE
0035: BCF 0A.3
0036: GOTO 037
.................... #include "tank.h"
.................... #include <16F88.h>
.................... //////// Standard Header file for the PIC16F88 device ////////////////
.................... #device PIC16F88
.................... #list
....................
.................... #device adc=8
.................... #fuses NOWDT,INTRC_IO, NOPUT, MCLR, NOBROWNOUT, NOLVP, NOCPD, NOWRT, NODEBUG, NOPROTECT, NOFCMEN, NOIESO
.................... #use delay(clock=4000000)
*
0047: MOVLW 12
0048: BSF 03.5
0049: SUBWF 22,F
004A: BTFSS 03.0
004B: GOTO 05A
004C: MOVLW A2
004D: MOVWF 04
004E: MOVLW FC
004F: ANDWF 00,F
0050: BCF 03.0
0051: RRF 00,F
0052: RRF 00,F
0053: MOVF 00,W
0054: BTFSC 03.2
0055: GOTO 05A
0056: GOTO 058
0057: NOP
0058: DECFSZ 00,F
0059: GOTO 057
005A: BCF 03.5
005B: RETLW 00
*
0088: MOVLW 75
0089: MOVWF 04
008A: MOVF 00,W
008B: BTFSC 03.2
008C: GOTO 09C
008D: MOVLW 01
008E: MOVWF 78
008F: CLRF 77
0090: DECFSZ 77,F
0091: GOTO 090
0092: DECFSZ 78,F
0093: GOTO 08F
0094: MOVLW 4A
0095: MOVWF 77
0096: DECFSZ 77,F
0097: GOTO 096
0098: NOP
0099: NOP
009A: DECFSZ 00,F
009B: GOTO 08D
009C: RETLW 00
....................
....................
....................
.................... #define DEBUG
....................
.................... #define TXo PIN_A3 // To the transmitter modulator
.................... #include "AX25.c" // podprogram pro prenos telemetrie
.................... #list
....................
....................
.................... unsigned int8 sensors; // pomocna promenna pro cteni cidel na caru
.................... unsigned int8 line; // na ktere strane byla detekovana cara
.................... unsigned int8 speed; // rychlost zataceni
.................... unsigned int8 rovinka; // pocitadlo pro zjisteni rovneho useku
.................... unsigned int8 last; // kde byla cara, kdyz byly minule cidla mimo
.................... unsigned int8 movement; // obsahuje aktualni smer zataceni
.................... unsigned int8 dira; // pocita dobu po kterou je ztracena cara
....................
.................... // Konstanty pro dynamiku pohybu
.................... #define T_DIRA 87 // po jakem case zataceni se detekuje dira
.................... #define INC_SPEED 1 // prirustek rychlosti v jednom kroku
.................... #define FW_POMALU 230 // trochu mimo caru vnitrni pas
.................... #define FW_ZATACKA 200 // rychlost vnejsiho kola pri zataceni
.................... #define FW_STREDNE 240 // trochu mimo caru vnejsi pas
.................... #define COUVANI 600 // couvnuti zpet na caru, po detekci diry
.................... #define PRES_DIRU 250
.................... #define MAX_ROVINKA (255-FW_STREDNE)
.................... #define TRESHOLD 10 // rozhodovaci uroven komparatoru, 0xF = 0.75*Vdd
.................... #define BUMPER_TRESHOLD 128
.................... #define CIK_CAK 30000
.................... #define T_CIHLA 50 // perioda detekce cihly
....................
.................... //motory //Napred vypnout potom zapnout!
.................... #define FR output_low(PIN_B5); output_high(PIN_B4) // Vpred
.................... #define FL output_low(PIN_B7); output_high(PIN_B6)
.................... #define BR output_low(PIN_B4); output_high(PIN_B5) // Vzad
.................... #define BL output_low(PIN_B6); output_high(PIN_B7)
.................... #define STOPR output_low(PIN_B4);output_low(PIN_B5) // Zastav
.................... #define STOPL output_low(PIN_B6);output_low(PIN_B7)
....................
.................... #define L 0b10 // left
.................... #define R 0b01 // right
.................... #define S 0b11 // straight
....................
.................... //cidla
.................... #define RSENSOR C2OUT // Senzory na caru
.................... #define LSENSOR C1OUT
.................... #define BUMPER PIN_A4 // Senzor na cihlu
....................
.................... #define DIAG_SERVO PIN_B3 // Propojka pro diagnosticky mod
.................... #define DIAG_SENSORS PIN_B2 // Propojka pro diagnosticky mod
....................
.................... #DEFINE SOUND_HI PIN_A6 // komplementarni vystupy pro piezo pipak
.................... #DEFINE SOUND_LO PIN_A7
....................
.................... char AXstring[40]; // Buffer pro prenos telemetrie
....................
.................... // makro pro PWM
.................... #define GO(motor, direction, power) if(get_timer0()<=power) \
.................... {direction##motor;} else {stop##motor;}
....................
.................... #int_TIMER2
.................... void TIMER2_isr()
.................... {
.................... if (speed<255) speed+=INC_SPEED;
*
0037: INCFSZ 42,W
0038: GOTO 03A
0039: GOTO 03C
003A: MOVLW 01
003B: ADDWF 42,F
.................... if (rovinka<MAX_ROVINKA) rovinka++;
003C: MOVF 43,W
003D: SUBLW 0E
003E: BTFSC 03.0
003F: INCF 43,F
.................... if (dira<=T_DIRA) dira++;
0040: MOVF 46,W
0041: SUBLW 57
0042: BTFSC 03.0
0043: INCF 46,F
.................... }
.................... // Primitivni Pipani
0044: BCF 0C.1
0045: BCF 0A.3
0046: GOTO 022
.................... void beep(unsigned int16 period, unsigned int16 length)
.................... {
.................... unsigned int16 nn;
....................
.................... for(nn=length; nn>0; nn--)
*
005C: MOVF 7D,W
005D: BSF 03.5
005E: MOVWF 21
005F: MOVF 7C,W
0060: MOVWF 20
0061: MOVF 20,F
0062: BTFSS 03.2
0063: GOTO 067
0064: MOVF 21,F
0065: BTFSC 03.2
0066: GOTO 086
.................... {
.................... output_high(SOUND_HI);output_low(SOUND_LO);
0067: BCF 05.6
0068: BCF 03.5
0069: BSF 05.6
006A: BSF 03.5
006B: BCF 05.7
006C: BCF 03.5
006D: BCF 05.7
.................... delay_us(period);
006E: MOVF 74,W
006F: BSF 03.5
0070: MOVWF 22
0071: BCF 03.5
0072: CALL 047
.................... output_high(SOUND_LO);output_low(SOUND_HI);
0073: BSF 03.5
0074: BCF 05.7
0075: BCF 03.5
0076: BSF 05.7
0077: BSF 03.5
0078: BCF 05.6
0079: BCF 03.5
007A: BCF 05.6
.................... delay_us(period);
007B: MOVF 74,W
007C: BSF 03.5
007D: MOVWF 22
007E: BCF 03.5
007F: CALL 047
.................... }
0080: BSF 03.5
0081: MOVF 20,W
0082: BTFSC 03.2
0083: DECF 21,F
0084: DECF 20,F
0085: GOTO 061
.................... }
0086: BCF 03.5
0087: RETLW 00
.................... /******************************************************************************/
.................... void diagnostika()
.................... {
.................... unsigned int16 n;
....................
.................... while (input(DIAG_SERVO)) // Propojka, ktera spousti diagnostiku
.................... {
*
009D: BSF 03.5
009E: BSF 06.3
009F: BCF 03.5
00A0: BTFSS 06.3
00A1: GOTO 1C8
.................... for (n=500; n<800; n+=100)
00A2: MOVLW 01
00A3: MOVWF 72
00A4: MOVLW F4
00A5: MOVWF 71
00A6: MOVF 72,W
00A7: SUBLW 03
00A8: BTFSS 03.0
00A9: GOTO 0BE
00AA: BTFSS 03.2
00AB: GOTO 0B0
00AC: MOVF 71,W
00AD: SUBLW 1F
00AE: BTFSS 03.0
00AF: GOTO 0BE
.................... {
.................... beep(n,n); //beep UP
00B0: MOVF 72,W
00B1: MOVWF 75
00B2: MOVF 71,W
00B3: MOVWF 74
00B4: MOVF 72,W
00B5: MOVWF 7D
00B6: MOVF 71,W
00B7: MOVWF 7C
00B8: CALL 05C
.................... };
00B9: MOVLW 64
00BA: ADDWF 71,F
00BB: BTFSC 03.0
00BC: INCF 72,F
00BD: GOTO 0A6
.................... Delay_ms(1000);
00BE: MOVLW 04
00BF: MOVWF 73
00C0: MOVLW FA
00C1: MOVWF 75
00C2: CALL 088
00C3: DECFSZ 73,F
00C4: GOTO 0C0
.................... //zastav vse
.................... STOPL; STOPR;
00C5: BSF 03.5
00C6: BCF 06.6
00C7: BCF 03.5
00C8: BCF 06.6
00C9: BSF 03.5
00CA: BCF 06.7
00CB: BCF 03.5
00CC: BCF 06.7
00CD: BSF 03.5
00CE: BCF 06.4
00CF: BCF 03.5
00D0: BCF 06.4
00D1: BSF 03.5
00D2: BCF 06.5
00D3: BCF 03.5
00D4: BCF 06.5
.................... //pravy pas
.................... FR; Delay_ms(1000); STOPR; Delay_ms(1000);
00D5: BSF 03.5
00D6: BCF 06.5
00D7: BCF 03.5
00D8: BCF 06.5
00D9: BSF 03.5
00DA: BCF 06.4
00DB: BCF 03.5
00DC: BSF 06.4
00DD: MOVLW 04
00DE: MOVWF 73
00DF: MOVLW FA
00E0: MOVWF 75
00E1: CALL 088
00E2: DECFSZ 73,F
00E3: GOTO 0DF
00E4: BSF 03.5
00E5: BCF 06.4
00E6: BCF 03.5
00E7: BCF 06.4
00E8: BSF 03.5
00E9: BCF 06.5
00EA: BCF 03.5
00EB: BCF 06.5
00EC: MOVLW 04
00ED: MOVWF 73
00EE: MOVLW FA
00EF: MOVWF 75
00F0: CALL 088
00F1: DECFSZ 73,F
00F2: GOTO 0EE
.................... BR; Delay_ms(1000); STOPR; Delay_ms(1000);
00F3: BSF 03.5
00F4: BCF 06.4
00F5: BCF 03.5
00F6: BCF 06.4
00F7: BSF 03.5
00F8: BCF 06.5
00F9: BCF 03.5
00FA: BSF 06.5
00FB: MOVLW 04
00FC: MOVWF 73
00FD: MOVLW FA
00FE: MOVWF 75
00FF: CALL 088
0100: DECFSZ 73,F
0101: GOTO 0FD
0102: BSF 03.5
0103: BCF 06.4
0104: BCF 03.5
0105: BCF 06.4
0106: BSF 03.5
0107: BCF 06.5
0108: BCF 03.5
0109: BCF 06.5
010A: MOVLW 04
010B: MOVWF 73
010C: MOVLW FA
010D: MOVWF 75
010E: CALL 088
010F: DECFSZ 73,F
0110: GOTO 10C
.................... Beep(880,100); Delay_ms(1000);
0111: MOVLW 03
0112: MOVWF 75
0113: MOVLW 70
0114: MOVWF 74
0115: CLRF 7D
0116: MOVLW 64
0117: MOVWF 7C
0118: CALL 05C
0119: MOVLW 04
011A: MOVWF 73
011B: MOVLW FA
011C: MOVWF 75
011D: CALL 088
011E: DECFSZ 73,F
011F: GOTO 11B
.................... //levy pas
.................... FL; Delay_ms(1000); STOPL; Delay_ms(1000);
0120: BSF 03.5
0121: BCF 06.7
0122: BCF 03.5
0123: BCF 06.7
0124: BSF 03.5
0125: BCF 06.6
0126: BCF 03.5
0127: BSF 06.6
0128: MOVLW 04
0129: MOVWF 73
012A: MOVLW FA
012B: MOVWF 75
012C: CALL 088
012D: DECFSZ 73,F
012E: GOTO 12A
012F: BSF 03.5
0130: BCF 06.6
0131: BCF 03.5
0132: BCF 06.6
0133: BSF 03.5
0134: BCF 06.7
0135: BCF 03.5
0136: BCF 06.7
0137: MOVLW 04
0138: MOVWF 73
0139: MOVLW FA
013A: MOVWF 75
013B: CALL 088
013C: DECFSZ 73,F
013D: GOTO 139
.................... BL; Delay_ms(1000); STOPL; Delay_ms(1000);
013E: BSF 03.5
013F: BCF 06.6
0140: BCF 03.5
0141: BCF 06.6
0142: BSF 03.5
0143: BCF 06.7
0144: BCF 03.5
0145: BSF 06.7
0146: MOVLW 04
0147: MOVWF 73
0148: MOVLW FA
0149: MOVWF 75
014A: CALL 088
014B: DECFSZ 73,F
014C: GOTO 148
014D: BSF 03.5
014E: BCF 06.6
014F: BCF 03.5
0150: BCF 06.6
0151: BSF 03.5
0152: BCF 06.7
0153: BCF 03.5
0154: BCF 06.7
0155: MOVLW 04
0156: MOVWF 73
0157: MOVLW FA
0158: MOVWF 75
0159: CALL 088
015A: DECFSZ 73,F
015B: GOTO 157
.................... Beep(880,100); Delay_ms(1000);
015C: MOVLW 03
015D: MOVWF 75
015E: MOVLW 70
015F: MOVWF 74
0160: CLRF 7D
0161: MOVLW 64
0162: MOVWF 7C
0163: CALL 05C
0164: MOVLW 04
0165: MOVWF 73
0166: MOVLW FA
0167: MOVWF 75
0168: CALL 088
0169: DECFSZ 73,F
016A: GOTO 166
.................... //oba pasy
.................... FL; FR; Delay_ms(1000); STOPL; STOPR; Delay_ms(1000);
016B: BSF 03.5
016C: BCF 06.7
016D: BCF 03.5
016E: BCF 06.7
016F: BSF 03.5
0170: BCF 06.6
0171: BCF 03.5
0172: BSF 06.6
0173: BSF 03.5
0174: BCF 06.5
0175: BCF 03.5
0176: BCF 06.5
0177: BSF 03.5
0178: BCF 06.4
0179: BCF 03.5
017A: BSF 06.4
017B: MOVLW 04
017C: MOVWF 73
017D: MOVLW FA
017E: MOVWF 75
017F: CALL 088
0180: DECFSZ 73,F
0181: GOTO 17D
0182: BSF 03.5
0183: BCF 06.6
0184: BCF 03.5
0185: BCF 06.6
0186: BSF 03.5
0187: BCF 06.7
0188: BCF 03.5
0189: BCF 06.7
018A: BSF 03.5
018B: BCF 06.4
018C: BCF 03.5
018D: BCF 06.4
018E: BSF 03.5
018F: BCF 06.5
0190: BCF 03.5
0191: BCF 06.5
0192: MOVLW 04
0193: MOVWF 73
0194: MOVLW FA
0195: MOVWF 75
0196: CALL 088
0197: DECFSZ 73,F
0198: GOTO 194
.................... BL; BR; Delay_ms(1000); STOPL; STOPR; Delay_ms(1000);
0199: BSF 03.5
019A: BCF 06.6
019B: BCF 03.5
019C: BCF 06.6
019D: BSF 03.5
019E: BCF 06.7
019F: BCF 03.5
01A0: BSF 06.7
01A1: BSF 03.5
01A2: BCF 06.4
01A3: BCF 03.5
01A4: BCF 06.4
01A5: BSF 03.5
01A6: BCF 06.5
01A7: BCF 03.5
01A8: BSF 06.5
01A9: MOVLW 04
01AA: MOVWF 73
01AB: MOVLW FA
01AC: MOVWF 75
01AD: CALL 088
01AE: DECFSZ 73,F
01AF: GOTO 1AB
01B0: BSF 03.5
01B1: BCF 06.6
01B2: BCF 03.5
01B3: BCF 06.6
01B4: BSF 03.5
01B5: BCF 06.7
01B6: BCF 03.5
01B7: BCF 06.7
01B8: BSF 03.5
01B9: BCF 06.4
01BA: BCF 03.5
01BB: BCF 06.4
01BC: BSF 03.5
01BD: BCF 06.5
01BE: BCF 03.5
01BF: BCF 06.5
01C0: MOVLW 04
01C1: MOVWF 73
01C2: MOVLW FA
01C3: MOVWF 75
01C4: CALL 088
01C5: DECFSZ 73,F
01C6: GOTO 1C2
.................... };
01C7: GOTO 09D
.................... while (input(DIAG_SENSORS))
.................... {
01C8: BSF 03.5
01C9: BSF 06.2
01CA: BCF 03.5
01CB: BTFSS 06.2
01CC: GOTO 1FB
.................... if (RSENSOR) beep(900,500);
01CD: BSF 03.5
01CE: BTFSS 1C.7
01CF: GOTO 1DB
01D0: MOVLW 03
01D1: MOVWF 75
01D2: MOVLW 84
01D3: MOVWF 74
01D4: MOVLW 01
01D5: MOVWF 7D
01D6: MOVLW F4
01D7: MOVWF 7C
01D8: BCF 03.5
01D9: CALL 05C
01DA: BSF 03.5
.................... if (LSENSOR) beep(800,500);
01DB: BTFSS 1C.6
01DC: GOTO 1E8
01DD: MOVLW 03
01DE: MOVWF 75
01DF: MOVLW 20
01E0: MOVWF 74
01E1: MOVLW 01
01E2: MOVWF 7D
01E3: MOVLW F4
01E4: MOVWF 7C
01E5: BCF 03.5
01E6: CALL 05C
01E7: BSF 03.5
.................... if ((read_adc(ADC_READ_ONLY)<BUMPER_TRESHOLD)) beep(1000,500);
01E8: BCF 03.5
01E9: BTFSS 1F.2
01EA: GOTO 1ED
01EB: BSF 03.5
01EC: GOTO 1E8
01ED: MOVF 1E,W
01EE: SUBLW 7F
01EF: BTFSS 03.0
01F0: GOTO 1FA
01F1: MOVLW 03
01F2: MOVWF 75
01F3: MOVLW E8
01F4: MOVWF 74
01F5: MOVLW 01
01F6: MOVWF 7D
01F7: MOVLW F4
01F8: MOVWF 7C
01F9: CALL 05C
.................... };
01FA: GOTO 1C8
.................... }
01FB: BCF 0A.3
01FC: GOTO 596 (RETURN)
.................... ///////////////////////////////////////////////////////////////////////////////
.................... void cikcak()
.................... {
.................... unsigned int16 n;
.................... sem1:
.................... n=CIK_CAK;
01FD: MOVLW 75
01FE: MOVWF 75
01FF: MOVLW 30
0200: MOVWF 74
.................... while (0==RSENSOR||LSENSOR) // zkontroluj caru
.................... {
0201: MOVLW 00
0202: BSF 03.5
0203: BTFSC 1C.7
0204: MOVLW 01
0205: XORLW 00
0206: BTFSC 03.2
0207: GOTO 20A
0208: BTFSS 1C.6
0209: GOTO 264
.................... if (n==CIK_CAK) // zmen smer zataceni
020A: MOVF 74,W
020B: SUBLW 30
020C: BTFSS 03.2
020D: GOTO 25E
020E: MOVF 75,W
020F: SUBLW 75
0210: BTFSS 03.2
0211: GOTO 25E
.................... {
.................... n=0;
0212: CLRF 75
0213: CLRF 74
.................... switch(movement)
.................... {
0214: BCF 03.5
0215: MOVF 45,W
0216: XORLW 02
0217: BTFSC 03.2
0218: GOTO 220
0219: XORLW 03
021A: BTFSC 03.2
021B: GOTO 233
021C: XORLW 02
021D: BTFSC 03.2
021E: GOTO 246
021F: GOTO 25D
.................... case L:
.................... FL;BR;
0220: BSF 03.5
0221: BCF 06.7
0222: BCF 03.5
0223: BCF 06.7
0224: BSF 03.5
0225: BCF 06.6
0226: BCF 03.5
0227: BSF 06.6
0228: BSF 03.5
0229: BCF 06.4
022A: BCF 03.5
022B: BCF 06.4
022C: BSF 03.5
022D: BCF 06.5
022E: BCF 03.5
022F: BSF 06.5
.................... movement=R;
0230: MOVLW 01
0231: MOVWF 45
.................... break;
0232: GOTO 25D
.................... case R:
.................... FR;BL;
0233: BSF 03.5
0234: BCF 06.5
0235: BCF 03.5
0236: BCF 06.5
0237: BSF 03.5
0238: BCF 06.4
0239: BCF 03.5
023A: BSF 06.4
023B: BSF 03.5
023C: BCF 06.6
023D: BCF 03.5
023E: BCF 06.6
023F: BSF 03.5
0240: BCF 06.7
0241: BCF 03.5
0242: BSF 06.7
.................... movement=L;
0243: MOVLW 02
0244: MOVWF 45
.................... break;
0245: GOTO 25D
.................... case S:
.................... FL;BR;
0246: BSF 03.5
0247: BCF 06.7
0248: BCF 03.5
0249: BCF 06.7
024A: BSF 03.5
024B: BCF 06.6
024C: BCF 03.5
024D: BSF 06.6
024E: BSF 03.5
024F: BCF 06.4
0250: BCF 03.5
0251: BCF 06.4
0252: BSF 03.5
0253: BCF 06.5
0254: BCF 03.5
0255: BSF 06.5
.................... movement=R;
0256: MOVLW 01
0257: MOVWF 45
.................... n=CIK_CAK/2;
0258: MOVLW 3A
0259: MOVWF 75
025A: MOVLW 98
025B: MOVWF 74
.................... break;
025C: GOTO 25D
025D: BSF 03.5
.................... }
.................... }
.................... n++;
025E: INCF 74,F
025F: BTFSC 03.2
0260: INCF 75,F
.................... }
0261: BCF 03.5
0262: GOTO 201
0263: BSF 03.5
.................... STOPL;STOPR;
0264: BCF 06.6
0265: BCF 03.5
0266: BCF 06.6
0267: BSF 03.5
0268: BCF 06.7
0269: BCF 03.5
026A: BCF 06.7
026B: BSF 03.5
026C: BCF 06.4
026D: BCF 03.5
026E: BCF 06.4
026F: BSF 03.5
0270: BCF 06.5
0271: BCF 03.5
0272: BCF 06.5
.................... line = RSENSOR; // cteni senzoru na caru
0273: CLRF 41
0274: BSF 03.5
0275: BTFSS 1C.7
0276: GOTO 27A
0277: BCF 03.5
0278: INCF 41,F
0279: BSF 03.5
.................... line |= LSENSOR << 1;
027A: MOVLW 00
027B: BTFSC 1C.6
027C: MOVLW 01
027D: MOVWF 77
027E: BCF 03.0
027F: RLF 77,F
0280: MOVF 77,W
0281: BCF 03.5
0282: IORWF 41,F
.................... if (line==0) goto sem1;
0283: MOVF 41,F
0284: BTFSC 03.2
0285: GOTO 1FD
.................... // nasli jsme caru
.................... line=S;
0286: MOVLW 03
0287: MOVWF 41
.................... }
0288: RETLW 00
.................... ///////////////////////////////////////////////////////////////////////////////
.................... void objizdka() // objede cihlu
.................... {
.................... unsigned int16 n;
....................
.................... BL;BR;Delay_ms(200);
0289: BSF 03.5
028A: BCF 06.6
028B: BCF 03.5
028C: BCF 06.6
028D: BSF 03.5
028E: BCF 06.7
028F: BCF 03.5
0290: BSF 06.7
0291: BSF 03.5
0292: BCF 06.4
0293: BCF 03.5
0294: BCF 06.4
0295: BSF 03.5
0296: BCF 06.5
0297: BCF 03.5
0298: BSF 06.5
0299: MOVLW C8
029A: MOVWF 75
029B: CALL 088
.................... STOPR;STOPL;
029C: BSF 03.5
029D: BCF 06.4
029E: BCF 03.5
029F: BCF 06.4
02A0: BSF 03.5
02A1: BCF 06.5
02A2: BCF 03.5
02A3: BCF 06.5
02A4: BSF 03.5
02A5: BCF 06.6
02A6: BCF 03.5
02A7: BCF 06.6
02A8: BSF 03.5
02A9: BCF 06.7
02AA: BCF 03.5
02AB: BCF 06.7
.................... beep(900,1000);
02AC: MOVLW 03
02AD: MOVWF 75
02AE: MOVLW 84
02AF: MOVWF 74
02B0: MOVLW 03
02B1: MOVWF 7D
02B2: MOVLW E8
02B3: MOVWF 7C
02B4: CALL 05C
.................... // movement=S;
.................... //cikcak();
....................
.................... BL; FR; Delay_ms(215); // otoc se 70° do leva
02B5: BSF 03.5
02B6: BCF 06.6
02B7: BCF 03.5
02B8: BCF 06.6
02B9: BSF 03.5
02BA: BCF 06.7
02BB: BCF 03.5
02BC: BSF 06.7
02BD: BSF 03.5
02BE: BCF 06.5
02BF: BCF 03.5
02C0: BCF 06.5
02C1: BSF 03.5
02C2: BCF 06.4
02C3: BCF 03.5
02C4: BSF 06.4
02C5: MOVLW D7
02C6: MOVWF 75
02C7: CALL 088
....................
.................... FR; FL; Delay_ms(600); // popojed rovne
02C8: BSF 03.5
02C9: BCF 06.5
02CA: BCF 03.5
02CB: BCF 06.5
02CC: BSF 03.5
02CD: BCF 06.4
02CE: BCF 03.5
02CF: BSF 06.4
02D0: BSF 03.5
02D1: BCF 06.7
02D2: BCF 03.5
02D3: BCF 06.7
02D4: BSF 03.5
02D5: BCF 06.6
02D6: BCF 03.5
02D7: BSF 06.6
02D8: MOVLW 03
02D9: MOVWF 73
02DA: MOVLW C8
02DB: MOVWF 75
02DC: CALL 088
02DD: DECFSZ 73,F
02DE: GOTO 2DA
....................
.................... BR; Delay_ms(50); // otoc se 90° do prava
02DF: BSF 03.5
02E0: BCF 06.4
02E1: BCF 03.5
02E2: BCF 06.4
02E3: BSF 03.5
02E4: BCF 06.5
02E5: BCF 03.5
02E6: BSF 06.5
02E7: MOVLW 32
02E8: MOVWF 75
02E9: CALL 088
.................... STOPR; FL; Delay_ms(600);
02EA: BSF 03.5
02EB: BCF 06.4
02EC: BCF 03.5
02ED: BCF 06.4
02EE: BSF 03.5
02EF: BCF 06.5
02F0: BCF 03.5
02F1: BCF 06.5
02F2: BSF 03.5
02F3: BCF 06.7
02F4: BCF 03.5
02F5: BCF 06.7
02F6: BSF 03.5
02F7: BCF 06.6
02F8: BCF 03.5
02F9: BSF 06.6
02FA: MOVLW 03
02FB: MOVWF 73
02FC: MOVLW C8
02FD: MOVWF 75
02FE: CALL 088
02FF: DECFSZ 73,F
0300: GOTO 2FC
....................
.................... FR; FL; Delay_ms(100); // popojed rovne na slepo
0301: BSF 03.5
0302: BCF 06.5
0303: BCF 03.5
0304: BCF 06.5
0305: BSF 03.5
0306: BCF 06.4
0307: BCF 03.5
0308: BSF 06.4
0309: BSF 03.5
030A: BCF 06.7
030B: BCF 03.5
030C: BCF 06.7
030D: BSF 03.5
030E: BCF 06.6
030F: BCF 03.5
0310: BSF 06.6
0311: MOVLW 64
0312: MOVWF 75
0313: CALL 088
.................... for(n=600;n>0;n--) // popojed rovne ale kontroluj caru
0314: MOVLW 02
0315: MOVWF 72
0316: MOVLW 58
0317: MOVWF 71
0318: MOVF 71,F
0319: BTFSS 03.2
031A: GOTO 31E
031B: MOVF 72,F
031C: BTFSC 03.2
031D: GOTO 33D
.................... {
.................... line = RSENSOR; // cteni senzoru na caru
031E: CLRF 41
031F: BSF 03.5
0320: BTFSS 1C.7
0321: GOTO 325
0322: BCF 03.5
0323: INCF 41,F
0324: BSF 03.5
.................... line |= LSENSOR << 1;
0325: MOVLW 00
0326: BTFSC 1C.6
0327: MOVLW 01
0328: MOVWF 77
0329: BCF 03.0
032A: RLF 77,F
032B: MOVF 77,W
032C: BCF 03.5
032D: IORWF 41,F
.................... if (line!=0) {Delay_ms(50); break;} // kdyz narazis na caru, za chvili zastav
032E: MOVF 41,F
032F: BTFSC 03.2
0330: GOTO 335
0331: MOVLW 32
0332: MOVWF 75
0333: CALL 088
0334: GOTO 33D
.................... Delay_ms(1);
0335: MOVLW 01
0336: MOVWF 75
0337: CALL 088
.................... }
0338: MOVF 71,W
0339: BTFSC 03.2
033A: DECF 72,F
033B: DECF 71,F
033C: GOTO 318
....................
.................... BL; // otoc se 60° do leva
033D: BSF 03.5
033E: BCF 06.6
033F: BCF 03.5
0340: BCF 06.6
0341: BSF 03.5
0342: BCF 06.7
0343: BCF 03.5
0344: BSF 06.7
.................... for(n=600;n>0;n--)
0345: MOVLW 02
0346: MOVWF 72
0347: MOVLW 58
0348: MOVWF 71
0349: MOVF 71,F
034A: BTFSS 03.2
034B: GOTO 34F
034C: MOVF 72,F
034D: BTFSC 03.2
034E: GOTO 36A
.................... {
.................... line = RSENSOR; // cteni senzoru na caru
034F: CLRF 41
0350: BSF 03.5
0351: BTFSS 1C.7
0352: GOTO 356
0353: BCF 03.5
0354: INCF 41,F
0355: BSF 03.5
.................... line |= LSENSOR << 1;
0356: MOVLW 00
0357: BTFSC 1C.6
0358: MOVLW 01
0359: MOVWF 77
035A: BCF 03.0
035B: RLF 77,F
035C: MOVF 77,W
035D: BCF 03.5
035E: IORWF 41,F
.................... if (line!=0) break;
035F: MOVF 41,F
0360: BTFSS 03.2
0361: GOTO 36A
.................... Delay_ms(1);
0362: MOVLW 01
0363: MOVWF 75
0364: CALL 088
.................... }
0365: MOVF 71,W
0366: BTFSC 03.2
0367: DECF 72,F
0368: DECF 71,F
0369: GOTO 349
.................... STOPR; STOPL;
036A: BSF 03.5
036B: BCF 06.4
036C: BCF 03.5
036D: BCF 06.4
036E: BSF 03.5
036F: BCF 06.5
0370: BCF 03.5
0371: BCF 06.5
0372: BSF 03.5
0373: BCF 06.6
0374: BCF 03.5
0375: BCF 06.6
0376: BSF 03.5
0377: BCF 06.7
0378: BCF 03.5
0379: BCF 06.7
....................
.................... movement=R;
037A: MOVLW 01
037B: MOVWF 45
.................... cikcak();
037C: CALL 1FD
.................... dira=0;
037D: CLRF 46
.................... }
037E: BCF 0A.3
037F: GOTO 5C6 (RETURN)
.................... ///////////////////////////////////////////////////////////////////////////////
.................... void prejeddiru() // vyresi diru
.................... {
.................... unsigned int16 n;
.................... unsigned int8 speed_dira;
....................
.................... STOPL;STOPR;
0380: BSF 03.5
0381: BCF 06.6
0382: BCF 03.5
0383: BCF 06.6
0384: BSF 03.5
0385: BCF 06.7
0386: BCF 03.5
0387: BCF 06.7
0388: BSF 03.5
0389: BCF 06.4
038A: BCF 03.5
038B: BCF 06.4
038C: BSF 03.5
038D: BCF 06.5
038E: BCF 03.5
038F: BCF 06.5
.................... speed_dira=speed;
0390: MOVF 42,W
0391: MOVWF 73
.................... beep(1000,500);
0392: MOVLW 03
0393: MOVWF 75
0394: MOVLW E8
0395: MOVWF 74
0396: MOVLW 01
0397: MOVWF 7D
0398: MOVLW F4
0399: MOVWF 7C
039A: CALL 05C
.................... switch (movement) //vrat se zpet na caru
.................... {
039B: MOVF 45,W
039C: XORLW 02
039D: BTFSC 03.2
039E: GOTO 3A6
039F: XORLW 03
03A0: BTFSC 03.2
03A1: GOTO 3DE
03A2: XORLW 02
03A3: BTFSC 03.2
03A4: GOTO 416
03A5: GOTO 418
.................... case L:
.................... for (n=COUVANI;n>0;n--) {GO(R,B,speed_dira); Delay_ms(1);}
03A6: MOVLW 02
03A7: MOVWF 72
03A8: MOVLW 58
03A9: MOVWF 71
03AA: MOVF 71,F
03AB: BTFSS 03.2
03AC: GOTO 3B0
03AD: MOVF 72,F
03AE: BTFSC 03.2
03AF: GOTO 3CD
03B0: MOVF 01,W
03B1: SUBWF 73,W
03B2: BTFSS 03.0
03B3: GOTO 3BD
03B4: BSF 03.5
03B5: BCF 06.4
03B6: BCF 03.5
03B7: BCF 06.4
03B8: BSF 03.5
03B9: BCF 06.5
03BA: BCF 03.5
03BB: BSF 06.5
03BC: GOTO 3C5
03BD: BSF 03.5
03BE: BCF 06.4
03BF: BCF 03.5
03C0: BCF 06.4
03C1: BSF 03.5
03C2: BCF 06.5
03C3: BCF 03.5
03C4: BCF 06.5
03C5: MOVLW 01
03C6: MOVWF 75
03C7: CALL 088
03C8: MOVF 71,W
03C9: BTFSC 03.2
03CA: DECF 72,F
03CB: DECF 71,F
03CC: GOTO 3AA
.................... STOPL;STOPR;
03CD: BSF 03.5
03CE: BCF 06.6
03CF: BCF 03.5
03D0: BCF 06.6
03D1: BSF 03.5
03D2: BCF 06.7
03D3: BCF 03.5
03D4: BCF 06.7
03D5: BSF 03.5
03D6: BCF 06.4
03D7: BCF 03.5
03D8: BCF 06.4
03D9: BSF 03.5
03DA: BCF 06.5
03DB: BCF 03.5
03DC: BCF 06.5
.................... break;
03DD: GOTO 418
.................... case R:
.................... for (n=COUVANI;n>0;n--) {GO(L,B,speed_dira); Delay_ms(1);}
03DE: MOVLW 02
03DF: MOVWF 72
03E0: MOVLW 58
03E1: MOVWF 71
03E2: MOVF 71,F
03E3: BTFSS 03.2
03E4: GOTO 3E8
03E5: MOVF 72,F
03E6: BTFSC 03.2
03E7: GOTO 405
03E8: MOVF 01,W
03E9: SUBWF 73,W
03EA: BTFSS 03.0
03EB: GOTO 3F5
03EC: BSF 03.5
03ED: BCF 06.6
03EE: BCF 03.5
03EF: BCF 06.6
03F0: BSF 03.5
03F1: BCF 06.7
03F2: BCF 03.5
03F3: BSF 06.7
03F4: GOTO 3FD
03F5: BSF 03.5
03F6: BCF 06.6
03F7: BCF 03.5
03F8: BCF 06.6
03F9: BSF 03.5
03FA: BCF 06.7
03FB: BCF 03.5
03FC: BCF 06.7
03FD: MOVLW 01
03FE: MOVWF 75
03FF: CALL 088
0400: MOVF 71,W
0401: BTFSC 03.2
0402: DECF 72,F
0403: DECF 71,F
0404: GOTO 3E2
.................... STOPL;STOPR;
0405: BSF 03.5
0406: BCF 06.6
0407: BCF 03.5
0408: BCF 06.6
0409: BSF 03.5
040A: BCF 06.7
040B: BCF 03.5
040C: BCF 06.7
040D: BSF 03.5
040E: BCF 06.4
040F: BCF 03.5
0410: BCF 06.4
0411: BSF 03.5
0412: BCF 06.5
0413: BCF 03.5
0414: BCF 06.5
.................... break;
0415: GOTO 418
.................... case S:
.................... goto sem;
0416: GOTO 4D2
.................... break;
0417: GOTO 418
.................... }
.................... beep(800,500);
0418: MOVLW 03
0419: MOVWF 75
041A: MOVLW 20
041B: MOVWF 74
041C: MOVLW 01
041D: MOVWF 7D
041E: MOVLW F4
041F: MOVWF 7C
0420: CALL 05C
....................
.................... line=0;
0421: CLRF 41
.................... FR; BL; Delay_ms(300); // otoc se na caru
0422: BSF 03.5
0423: BCF 06.5
0424: BCF 03.5
0425: BCF 06.5
0426: BSF 03.5
0427: BCF 06.4
0428: BCF 03.5
0429: BSF 06.4
042A: BSF 03.5
042B: BCF 06.6
042C: BCF 03.5
042D: BCF 06.6
042E: BSF 03.5
042F: BCF 06.7
0430: BCF 03.5
0431: BSF 06.7
0432: MOVLW 02
0433: MOVWF 74
0434: MOVLW 96
0435: MOVWF 75
0436: CALL 088
0437: DECFSZ 74,F
0438: GOTO 434
.................... while(line==0)
.................... {
0439: MOVF 41,F
043A: BTFSS 03.2
043B: GOTO 44D
.................... line = RSENSOR; // cteni senzoru na caru
043C: CLRF 41
043D: BSF 03.5
043E: BTFSS 1C.7
043F: GOTO 443
0440: BCF 03.5
0441: INCF 41,F
0442: BSF 03.5
.................... line |= LSENSOR << 1;
0443: MOVLW 00
0444: BTFSC 1C.6
0445: MOVLW 01
0446: MOVWF 77
0447: BCF 03.0
0448: RLF 77,F
0449: MOVF 77,W
044A: BCF 03.5
044B: IORWF 41,F
.................... }
044C: GOTO 439
.................... FL;BR; Delay_ms(60);
044D: BSF 03.5
044E: BCF 06.7
044F: BCF 03.5
0450: BCF 06.7
0451: BSF 03.5
0452: BCF 06.6
0453: BCF 03.5
0454: BSF 06.6
0455: BSF 03.5
0456: BCF 06.4
0457: BCF 03.5
0458: BCF 06.4
0459: BSF 03.5
045A: BCF 06.5
045B: BCF 03.5
045C: BSF 06.5
045D: MOVLW 3C
045E: MOVWF 75
045F: CALL 088
.................... STOPL; STOPR;
0460: BSF 03.5
0461: BCF 06.6
0462: BCF 03.5
0463: BCF 06.6
0464: BSF 03.5
0465: BCF 06.7
0466: BCF 03.5
0467: BCF 06.7
0468: BSF 03.5
0469: BCF 06.4
046A: BCF 03.5
046B: BCF 06.4
046C: BSF 03.5
046D: BCF 06.5
046E: BCF 03.5
046F: BCF 06.5
....................
.................... FL; BR; Delay_ms(500);
0470: BSF 03.5
0471: BCF 06.7
0472: BCF 03.5
0473: BCF 06.7
0474: BSF 03.5
0475: BCF 06.6
0476: BCF 03.5
0477: BSF 06.6
0478: BSF 03.5
0479: BCF 06.4
047A: BCF 03.5
047B: BCF 06.4
047C: BSF 03.5
047D: BCF 06.5
047E: BCF 03.5
047F: BSF 06.5
0480: MOVLW 02
0481: MOVWF 74
0482: MOVLW FA
0483: MOVWF 75
0484: CALL 088
0485: DECFSZ 74,F
0486: GOTO 482
.................... STOPL; STOPR;
0487: BSF 03.5
0488: BCF 06.6
0489: BCF 03.5
048A: BCF 06.6
048B: BSF 03.5
048C: BCF 06.7
048D: BCF 03.5
048E: BCF 06.7
048F: BSF 03.5
0490: BCF 06.4
0491: BCF 03.5
0492: BCF 06.4
0493: BSF 03.5
0494: BCF 06.5
0495: BCF 03.5
0496: BCF 06.5
....................
.................... Delay_ms(1000);
0497: MOVLW 04
0498: MOVWF 74
0499: MOVLW FA
049A: MOVWF 75
049B: CALL 088
049C: DECFSZ 74,F
049D: GOTO 499
....................
.................... FR;FL; //popojed rovne
049E: BSF 03.5
049F: BCF 06.5
04A0: BCF 03.5
04A1: BCF 06.5
04A2: BSF 03.5
04A3: BCF 06.4
04A4: BCF 03.5
04A5: BSF 06.4
04A6: BSF 03.5
04A7: BCF 06.7
04A8: BCF 03.5
04A9: BCF 06.7
04AA: BSF 03.5
04AB: BCF 06.6
04AC: BCF 03.5
04AD: BSF 06.6
.................... for(n=PRES_DIRU;n>0;n--)
04AE: CLRF 72
04AF: MOVLW FA
04B0: MOVWF 71
04B1: MOVF 71,F
04B2: BTFSS 03.2
04B3: GOTO 4B7
04B4: MOVF 72,F
04B5: BTFSC 03.2
04B6: GOTO 4D2
.................... {
.................... line = RSENSOR; // cteni senzoru na caru
04B7: CLRF 41
04B8: BSF 03.5
04B9: BTFSS 1C.7
04BA: GOTO 4BE
04BB: BCF 03.5
04BC: INCF 41,F
04BD: BSF 03.5
.................... line |= LSENSOR << 1;
04BE: MOVLW 00
04BF: BTFSC 1C.6
04C0: MOVLW 01
04C1: MOVWF 77
04C2: BCF 03.0
04C3: RLF 77,F
04C4: MOVF 77,W
04C5: BCF 03.5
04C6: IORWF 41,F
.................... if (line!=0) break;
04C7: MOVF 41,F
04C8: BTFSS 03.2
04C9: GOTO 4D2
.................... Delay_ms(1);
04CA: MOVLW 01
04CB: MOVWF 75
04CC: CALL 088
.................... }
04CD: MOVF 71,W
04CE: BTFSC 03.2
04CF: DECF 72,F
04D0: DECF 71,F
04D1: GOTO 4B1
.................... sem:
.................... STOPL; STOPR;
04D2: BSF 03.5
04D3: BCF 06.6
04D4: BCF 03.5
04D5: BCF 06.6
04D6: BSF 03.5
04D7: BCF 06.7
04D8: BCF 03.5
04D9: BCF 06.7
04DA: BSF 03.5
04DB: BCF 06.4
04DC: BCF 03.5
04DD: BCF 06.4
04DE: BSF 03.5
04DF: BCF 06.5
04E0: BCF 03.5
04E1: BCF 06.5
.................... movement=S;
04E2: MOVLW 03
04E3: MOVWF 45
.................... cikcak(); // najdi caru
04E4: CALL 1FD
.................... dira=0;
04E5: CLRF 46
.................... }
04E6: BCF 0A.3
04E7: GOTO 65C (RETURN)
.................... ///////////////////////////////////////////////////////////////////////////////
.................... void main()
.................... {
04E8: CLRF 04
04E9: MOVLW 1F
04EA: ANDWF 03,F
04EB: BSF 03.5
04EC: BCF 1F.4
04ED: BCF 1F.5
04EE: MOVF 1B,W
04EF: ANDLW 80
04F0: MOVWF 1B
04F1: MOVLW 07
04F2: MOVWF 1C
04F3: MOVF 1C,W
04F4: BCF 03.5
04F5: BCF 0D.6
04F6: MOVLW 60
04F7: BSF 03.5
04F8: MOVWF 0F
.................... unsigned int16 n; // pro FOR
....................
.................... STOPL; STOPR; // prepne vystupy na ovladani motoru na output a zastavi
*
0515: BSF 03.5
0516: BCF 06.6
0517: BCF 03.5
0518: BCF 06.6
0519: BSF 03.5
051A: BCF 06.7
051B: BCF 03.5
051C: BCF 06.7
051D: BSF 03.5
051E: BCF 06.4
051F: BCF 03.5
0520: BCF 06.4
0521: BSF 03.5
0522: BCF 06.5
0523: BCF 03.5
0524: BCF 06.5
....................
.................... setup_oscillator(OSC_4MHZ|OSC_INTRC); // 4 MHz interni RC oscilator
0525: MOVLW 62
0526: BSF 03.5
0527: MOVWF 0F
....................
.................... port_b_pullups(TRUE); // pullups pro piano na diagnostiku
0528: BCF 01.7
.................... setup_spi(FALSE);
0529: BCF 03.5
052A: BCF 14.5
052B: BSF 03.5
052C: BCF 06.2
052D: BSF 06.1
052E: BCF 06.4
052F: MOVLW 00
0530: BCF 03.5
0531: MOVWF 14
0532: BSF 03.5
0533: MOVWF 14
.................... setup_timer_0(RTCC_INTERNAL|RTCC_DIV_1); // Casovac pro PWM
0534: MOVF 01,W
0535: ANDLW C7
0536: IORLW 08
0537: MOVWF 01
....................
.................... setup_timer_2(T2_DIV_BY_4,255,10); // Casovac pro regulaci
0538: MOVLW 48
0539: MOVWF 78
053A: IORLW 05
053B: BCF 03.5
053C: MOVWF 12
053D: MOVLW FF
053E: BSF 03.5
053F: MOVWF 12
.................... // preruseni kazdych 10ms
.................... setup_adc_ports(sAN2|VSS_VDD); // nastaveni A/D prevodniku pro naraznik
0540: BCF 1F.4
0541: BCF 1F.5
0542: MOVF 1B,W
0543: ANDLW 80
0544: IORLW 04
0545: MOVWF 1B
.................... setup_adc(ADC_CLOCK_INTERNAL);
0546: BCF 1F.6
0547: BCF 03.5
0548: BSF 1F.6
0549: BSF 1F.7
054A: BSF 03.5
054B: BCF 1F.7
054C: BCF 03.5
054D: BSF 1F.0
.................... set_adc_channel(2);
054E: MOVLW 10
054F: MOVWF 78
0550: MOVF 1F,W
0551: ANDLW C7
0552: IORWF 78,W
0553: MOVWF 1F
.................... setup_timer_1(T1_INTERNAL|T1_DIV_BY_1); // Casovac pro naraznik
0554: MOVLW 85
0555: MOVWF 10
.................... setup_ccp1(CCP_COMPARE_RESET_TIMER);
0556: BSF 03.5
0557: BSF 06.3
0558: MOVLW 0B
0559: BCF 03.5
055A: MOVWF 17
.................... CCP_1=(2^10)-1; // prevod kazdou 1ms
055B: CLRF 16
055C: MOVLW 07
055D: MOVWF 15
....................
.................... setup_comparator(A0_VR_A1_VR); // inicializace komparatoru pro cidla cary
055E: MOVLW 02
055F: BSF 03.5
0560: MOVWF 1C
0561: MOVF 05,W
0562: IORLW 03
0563: MOVWF 05
0564: MOVLW 03
0565: MOVWF 77
0566: DECFSZ 77,F
0567: GOTO 566
0568: MOVF 1C,W
0569: BCF 03.5
056A: BCF 0D.6
.................... setup_vref(VREF_HIGH|TRESHOLD); // 32 kroku od 0.25 do 0.75 Vdd
056B: MOVLW 8A
056C: BSF 03.5
056D: MOVWF 1D
....................
.................... Beep(1000,200); //double beep
056E: MOVLW 03
056F: MOVWF 75
0570: MOVLW E8
0571: MOVWF 74
0572: CLRF 7D
0573: MOVLW C8
0574: MOVWF 7C
0575: BCF 03.5
0576: CALL 05C
.................... Delay_ms(50);
0577: MOVLW 32
0578: MOVWF 75
0579: CALL 088
.................... Beep(1000,200);
057A: MOVLW 03
057B: MOVWF 75
057C: MOVLW E8
057D: MOVWF 74
057E: CLRF 7D
057F: MOVLW C8
0580: MOVWF 7C
0581: CALL 05C
.................... Delay_ms(1000); // 1s
0582: MOVLW 04
0583: MOVWF 71
0584: MOVLW FA
0585: MOVWF 75
0586: CALL 088
0587: DECFSZ 71,F
0588: GOTO 584
....................
.................... // povoleni rizeni rychlosti zataceni pres preruseni
.................... enable_interrupts(INT_TIMER2);
0589: BSF 03.5
058A: BSF 0C.1
.................... enable_interrupts(GLOBAL);
058B: MOVLW C0
058C: BCF 03.5
058D: IORWF 0B,F
....................
.................... /*---------------------------------------------------------------------------*/
.................... sensors=S;
058E: MOVLW 03
058F: MOVWF 40
.................... line=S;
0590: MOVWF 41
.................... last=S;
0591: MOVWF 44
.................... movement=S;
0592: MOVWF 45
.................... speed=FW_POMALU;
0593: MOVLW E6
0594: MOVWF 42
....................
.................... diagnostika();
0595: GOTO 09D
.................... // cikcak(); // toc se, abys nasel caru
.................... Delay_ms(500);
0596: MOVLW 02
0597: MOVWF 71
0598: MOVLW FA
0599: MOVWF 75
059A: CALL 088
059B: DECFSZ 71,F
059C: GOTO 598
.................... Beep(1000,200);
059D: MOVLW 03
059E: MOVWF 75
059F: MOVLW E8
05A0: MOVWF 74
05A1: CLRF 7D
05A2: MOVLW C8
05A3: MOVWF 7C
05A4: CALL 05C
.................... Delay_ms(500);
05A5: MOVLW 02
05A6: MOVWF 71
05A7: MOVLW FA
05A8: MOVWF 75
05A9: CALL 088
05AA: DECFSZ 71,F
05AB: GOTO 5A7
....................
.................... while(true) // hlavni smycka (jizda podle cary)
.................... {
.................... sensors = RSENSOR; // cteni senzoru na caru
05AC: CLRF 40
05AD: BSF 03.5
05AE: BTFSS 1C.7
05AF: GOTO 5B3
05B0: BCF 03.5
05B1: INCF 40,F
05B2: BSF 03.5
.................... sensors |= LSENSOR << 1;
05B3: MOVLW 00
05B4: BTFSC 1C.6
05B5: MOVLW 01
05B6: MOVWF 77
05B7: BCF 03.0
05B8: RLF 77,F
05B9: MOVF 77,W
05BA: BCF 03.5
05BB: IORWF 40,F
....................
.................... if ((read_adc(ADC_READ_ONLY)<BUMPER_TRESHOLD) && (dira<=T_CIHLA)) objizdka();
05BC: BTFSC 1F.2
05BD: GOTO 5BC
05BE: MOVF 1E,W
05BF: SUBLW 7F
05C0: BTFSS 03.0
05C1: GOTO 5C6
05C2: MOVF 46,W
05C3: SUBLW 32
05C4: BTFSC 03.0
05C5: GOTO 289
....................
.................... switch (sensors) // zatacej podle toho, kde vidis caru
.................... {
05C6: MOVF 40,W
05C7: XORLW 03
05C8: BTFSC 03.2
05C9: GOTO 5D1
05CA: XORLW 01
05CB: BTFSC 03.2
05CC: GOTO 5E5
05CD: XORLW 03
05CE: BTFSC 03.2
05CF: GOTO 61E
05D0: GOTO 657
.................... case S: // rovne
.................... FL; FR; // pokud se jede dlouho rovne, tak pridej
05D1: BSF 03.5
05D2: BCF 06.7
05D3: BCF 03.5
05D4: BCF 06.7
05D5: BSF 03.5
05D6: BCF 06.6
05D7: BCF 03.5
05D8: BSF 06.6
05D9: BSF 03.5
05DA: BCF 06.5
05DB: BCF 03.5
05DC: BCF 06.5
05DD: BSF 03.5
05DE: BCF 06.4
05DF: BCF 03.5
05E0: BSF 06.4
.................... dira=0;
05E1: CLRF 46
.................... movement=S;
05E2: MOVLW 03
05E3: MOVWF 45
.................... continue;
05E4: GOTO 5AC
.................... case L: // trochu vlevo
.................... GO(L, F, FW_POMALU+rovinka); GO(R, F, FW_STREDNE+rovinka);
05E5: MOVF 01,W
05E6: MOVWF 71
05E7: MOVLW E6
05E8: ADDWF 43,W
05E9: SUBWF 71,W
05EA: BTFSC 03.2
05EB: GOTO 5EE
05EC: BTFSC 03.0
05ED: GOTO 5F7
05EE: BSF 03.5
05EF: BCF 06.7
05F0: BCF 03.5
05F1: BCF 06.7
05F2: BSF 03.5
05F3: BCF 06.6
05F4: BCF 03.5
05F5: BSF 06.6
05F6: GOTO 5FF
05F7: BSF 03.5
05F8: BCF 06.6
05F9: BCF 03.5
05FA: BCF 06.6
05FB: BSF 03.5
05FC: BCF 06.7
05FD: BCF 03.5
05FE: BCF 06.7
05FF: MOVF 01,W
0600: MOVWF 71
0601: MOVLW F0
0602: ADDWF 43,W
0603: SUBWF 71,W
0604: BTFSC 03.2
0605: GOTO 608
0606: BTFSC 03.0
0607: GOTO 611
0608: BSF 03.5
0609: BCF 06.5
060A: BCF 03.5
060B: BCF 06.5
060C: BSF 03.5
060D: BCF 06.4
060E: BCF 03.5
060F: BSF 06.4
0610: GOTO 619
0611: BSF 03.5
0612: BCF 06.4
0613: BCF 03.5
0614: BCF 06.4
0615: BSF 03.5
0616: BCF 06.5
0617: BCF 03.5
0618: BCF 06.5
.................... line=L;
0619: MOVLW 02
061A: MOVWF 41
.................... dira=0;
061B: CLRF 46
.................... movement=L;
061C: MOVWF 45
.................... continue;
061D: GOTO 5AC
.................... case R: // trochu vpravo
.................... GO(R, F, FW_POMALU+rovinka); GO(L, F, FW_STREDNE+rovinka);
061E: MOVF 01,W
061F: MOVWF 71
0620: MOVLW E6
0621: ADDWF 43,W
0622: SUBWF 71,W
0623: BTFSC 03.2
0624: GOTO 627
0625: BTFSC 03.0
0626: GOTO 630
0627: BSF 03.5
0628: BCF 06.5
0629: BCF 03.5
062A: BCF 06.5
062B: BSF 03.5
062C: BCF 06.4
062D: BCF 03.5
062E: BSF 06.4
062F: GOTO 638
0630: BSF 03.5
0631: BCF 06.4
0632: BCF 03.5
0633: BCF 06.4
0634: BSF 03.5
0635: BCF 06.5
0636: BCF 03.5
0637: BCF 06.5
0638: MOVF 01,W
0639: MOVWF 71
063A: MOVLW F0
063B: ADDWF 43,W
063C: SUBWF 71,W
063D: BTFSC 03.2
063E: GOTO 641
063F: BTFSC 03.0
0640: GOTO 64A
0641: BSF 03.5
0642: BCF 06.7
0643: BCF 03.5
0644: BCF 06.7
0645: BSF 03.5
0646: BCF 06.6
0647: BCF 03.5
0648: BSF 06.6
0649: GOTO 652
064A: BSF 03.5
064B: BCF 06.6
064C: BCF 03.5
064D: BCF 06.6
064E: BSF 03.5
064F: BCF 06.7
0650: BCF 03.5
0651: BCF 06.7
.................... line=R;
0652: MOVLW 01
0653: MOVWF 41
.................... dira=0;
0654: CLRF 46
.................... movement=R;
0655: MOVWF 45
.................... continue;
0656: GOTO 5AC
.................... default: // kdyz jsou obe cidla mimo caru, tak pokracuj dal
.................... }
.................... rovinka=0;
0657: CLRF 43
.................... if (dira>=T_DIRA) prejeddiru();
0658: MOVF 46,W
0659: SUBLW 56
065A: BTFSS 03.0
065B: GOTO 380
.................... if (last!=line) // pokud si prejel caru z jedne strany na druhou stranu, tak zabrzdi
065C: MOVF 41,W
065D: SUBWF 44,W
065E: BTFSC 03.2
065F: GOTO 664
.................... {
.................... last=line;
0660: MOVF 41,W
0661: MOVWF 44
.................... speed=FW_ZATACKA;
0662: MOVLW C8
0663: MOVWF 42
.................... }
.................... if (L==line) // kdyz jsou obe cidla mimo caru, zatoc na caru
0664: MOVF 41,W
0665: SUBLW 02
0666: BTFSS 03.2
0667: GOTO 688
.................... {
.................... STOPL;
0668: BSF 03.5
0669: BCF 06.6
066A: BCF 03.5
066B: BCF 06.6
066C: BSF 03.5
066D: BCF 06.7
066E: BCF 03.5
066F: BCF 06.7
.................... GO(R, F, speed);
0670: MOVF 01,W
0671: SUBWF 42,W
0672: BTFSS 03.0
0673: GOTO 67D
0674: BSF 03.5
0675: BCF 06.5
0676: BCF 03.5
0677: BCF 06.5
0678: BSF 03.5
0679: BCF 06.4
067A: BCF 03.5
067B: BSF 06.4
067C: GOTO 685
067D: BSF 03.5
067E: BCF 06.4
067F: BCF 03.5
0680: BCF 06.4
0681: BSF 03.5
0682: BCF 06.5
0683: BCF 03.5
0684: BCF 06.5
.................... movement=L;
0685: MOVLW 02
0686: MOVWF 45
.................... }
.................... else
0687: GOTO 6A7
.................... {
.................... STOPR;
0688: BSF 03.5
0689: BCF 06.4
068A: BCF 03.5
068B: BCF 06.4
068C: BSF 03.5
068D: BCF 06.5
068E: BCF 03.5
068F: BCF 06.5
.................... GO(L, F, speed);
0690: MOVF 01,W
0691: SUBWF 42,W
0692: BTFSS 03.0
0693: GOTO 69D
0694: BSF 03.5
0695: BCF 06.7
0696: BCF 03.5
0697: BCF 06.7
0698: BSF 03.5
0699: BCF 06.6
069A: BCF 03.5
069B: BSF 06.6
069C: GOTO 6A5
069D: BSF 03.5
069E: BCF 06.6
069F: BCF 03.5
06A0: BCF 06.6
06A1: BSF 03.5
06A2: BCF 06.7
06A3: BCF 03.5
06A4: BCF 06.7
.................... movement=R;
06A5: MOVLW 01
06A6: MOVWF 45
.................... }
.................... } // while(true)
06A7: GOTO 5AC
.................... }
....................
....................
06A8: SLEEP
 
Configuration Fuses:
Word 1: 3F38 NOWDT NOPUT MCLR NOBROWNOUT NOLVP NOCPD NOWRT NODEBUG CCPB0 NOPROTECT INTRC_IO
Word 2: 3FFC NOFCMEN NOIESO
/roboti/istrobot/merkur/PIC16F88/turn_L/tank.PJT
0,0 → 1,40
[PROJECT]
Target=tank.HEX
Development_Mode=
Processor=0x688F
ToolSuite=CCS
 
[Directories]
Include=C:\Program Files\PICC\devices\;C:\Program Files\PICC\drivers\;C:\library\CCS;
Library=
LinkerScript=
 
[Target Data]
FileList=tank.c;
BuildTool=C-COMPILER
OptionString=+FM
AdditionalOptionString=
BuildRequired=1
 
[tank.c]
Type=4
Path=
FileList=
BuildTool=
OptionString=
AdditionalOptionString=
 
[mru-list]
1=tank.c
 
[Windows]
0=0000 tank.c 0 0 796 451 3 0
 
[Opened Files]
1=D:\KAKLIK\programy\PIC_C\roboti\merkur\PIC16F88\turn_L\tank.c
2=C:\Program Files\PICC\devices\16F88.h
3=
4=C:\Program Files\PICC\devices\16F88.h
5=
6=
7=
/roboti/istrobot/merkur/PIC16F88/turn_L/tank.SYM
0,0 → 1,88
003 STATUS
015-016 CCP_1
015 CCP_1_LOW
016 CCP_1_HIGH
020 @INTERRUPT_AREA
021 @INTERRUPT_AREA
022 @INTERRUPT_AREA
023 @INTERRUPT_AREA
024 @INTERRUPT_AREA
025 @INTERRUPT_AREA
026 @INTERRUPT_AREA
027 @INTERRUPT_AREA
028 @INTERRUPT_AREA
029-038 SendData
039.0 bit
03A fcslo
03B fcshi
03C stuff
03D flag_flag
03E fcs_flag
03F i
040 sensors
041 line
042 speed
043 rovinka
044 last
045 movement
046 dira
047-06E AXstring
06F-070 main.n
071-072 objizdka.n
071-072 diagnostika.n
071-072 prejeddiru.n
071 main.@SCRATCH
073 prejeddiru.speed_dira
073 diagnostika.@SCRATCH
073 objizdka.@SCRATCH
074-075 beep.period
074-075 cikcak.n
074 prejeddiru.@SCRATCH
075 @delay_ms1.P1
076 cikcak.@SCRATCH
077 @SCRATCH
078 @SCRATCH
078 _RETURN_
079 @SCRATCH
07A @SCRATCH
07B @SCRATCH
07C-07D beep.length
09C.6 C1OUT
09C.7 C2OUT
0A0-0A1 beep.nn
0A2 @delay_us1.P1
 
0088 @delay_ms1
0047 @delay_us1
0037 TIMER2_isr
005C beep
009D diagnostika
01FD cikcak
0289 objizdka
0380 prejeddiru
04E8 main
04E8 @cinit
01FD sem1
04D2 sem
 
Project Files:
D:\KAKLIK\programy\PIC_C\roboti\merkur\PIC16F88\turn_L\tank.c
D:\KAKLIK\programy\PIC_C\roboti\merkur\PIC16F88\turn_L\tank.h
C:\Program Files\PICC\devices\16F88.h
D:\KAKLIK\programy\PIC_C\roboti\merkur\PIC16F88\turn_L\AX25.c
 
Compiler Settings:
Processor: PIC16F88
Pointer Size: 8
ADC Range: 0-255
Opt Level: 9
Short,Int,Long: 1,8,16
 
Output Files:
Errors: D:\KAKLIK\programy\PIC_C\roboti\merkur\PIC16F88\turn_L\tank.err
INHX8: D:\KAKLIK\programy\PIC_C\roboti\merkur\PIC16F88\turn_L\tank.HEX
Symbols: D:\KAKLIK\programy\PIC_C\roboti\merkur\PIC16F88\turn_L\tank.SYM
List: D:\KAKLIK\programy\PIC_C\roboti\merkur\PIC16F88\turn_L\tank.LST
Debug/COFF: D:\KAKLIK\programy\PIC_C\roboti\merkur\PIC16F88\turn_L\tank.cof
Call Tree: D:\KAKLIK\programy\PIC_C\roboti\merkur\PIC16F88\turn_L\tank.tre
Statistics: D:\KAKLIK\programy\PIC_C\roboti\merkur\PIC16F88\turn_L\tank.sta
/roboti/istrobot/merkur/PIC16F88/turn_L/tank.c
0,0 → 1,340
#include "tank.h"
 
#define DEBUG
 
#define TXo PIN_A3 // To the transmitter modulator
#include "AX25.c" // podprogram pro prenos telemetrie
 
unsigned int8 sensors; // pomocna promenna pro cteni cidel na caru
unsigned int8 line; // na ktere strane byla detekovana cara
unsigned int8 speed; // rychlost zataceni
unsigned int8 rovinka; // pocitadlo pro zjisteni rovneho useku
unsigned int8 last; // kde byla cara, kdyz byly minule cidla mimo
unsigned int8 movement; // obsahuje aktualni smer zataceni
unsigned int8 dira; // pocita dobu po kterou je ztracena cara
 
// Konstanty pro dynamiku pohybu
#define T_DIRA 87 // po jakem case zataceni se detekuje dira
#define INC_SPEED 1 // prirustek rychlosti v jednom kroku
#define FW_POMALU 230 // trochu mimo caru vnitrni pas
#define FW_ZATACKA 200 // rychlost vnejsiho kola pri zataceni
#define FW_STREDNE 240 // trochu mimo caru vnejsi pas
#define COUVANI 600 // couvnuti zpet na caru, po detekci diry
#define PRES_DIRU 250
#define MAX_ROVINKA (255-FW_STREDNE)
#define TRESHOLD 10 // rozhodovaci uroven komparatoru, 0xF = 0.75*Vdd
#define BUMPER_TRESHOLD 128
#define CIK_CAK 30000
#define T_CIHLA 50 // perioda detekce cihly
 
//motory //Napred vypnout potom zapnout!
#define FR output_low(PIN_B5); output_high(PIN_B4) // Vpred
#define FL output_low(PIN_B7); output_high(PIN_B6)
#define BR output_low(PIN_B4); output_high(PIN_B5) // Vzad
#define BL output_low(PIN_B6); output_high(PIN_B7)
#define STOPR output_low(PIN_B4);output_low(PIN_B5) // Zastav
#define STOPL output_low(PIN_B6);output_low(PIN_B7)
 
#define L 0b10 // left
#define R 0b01 // right
#define S 0b11 // straight
 
//cidla
#define RSENSOR C2OUT // Senzory na caru
#define LSENSOR C1OUT
#define BUMPER PIN_A4 // Senzor na cihlu
 
#define DIAG_SERVO PIN_B3 // Propojka pro diagnosticky mod
#define DIAG_SENSORS PIN_B2 // Propojka pro diagnosticky mod
 
#DEFINE SOUND_HI PIN_A6 // komplementarni vystupy pro piezo pipak
#DEFINE SOUND_LO PIN_A7
 
char AXstring[40]; // Buffer pro prenos telemetrie
 
// makro pro PWM
#define GO(motor, direction, power) if(get_timer0()<=power) \
{direction##motor;} else {stop##motor;}
 
#int_TIMER2
void TIMER2_isr()
{
if (speed<255) speed+=INC_SPEED;
if (rovinka<MAX_ROVINKA) rovinka++;
if (dira<=T_DIRA) dira++;
}
// Primitivni Pipani
void beep(unsigned int16 period, unsigned int16 length)
{
unsigned int16 nn;
 
for(nn=length; nn>0; nn--)
{
output_high(SOUND_HI);output_low(SOUND_LO);
delay_us(period);
output_high(SOUND_LO);output_low(SOUND_HI);
delay_us(period);
}
}
/******************************************************************************/
void diagnostika()
{
unsigned int16 n;
 
while (input(DIAG_SERVO)) // Propojka, ktera spousti diagnostiku
{
for (n=500; n<800; n+=100)
{
beep(n,n); //beep UP
};
Delay_ms(1000);
//zastav vse
STOPL; STOPR;
//pravy pas
FR; Delay_ms(1000); STOPR; Delay_ms(1000);
BR; Delay_ms(1000); STOPR; Delay_ms(1000);
Beep(880,100); Delay_ms(1000);
//levy pas
FL; Delay_ms(1000); STOPL; Delay_ms(1000);
BL; Delay_ms(1000); STOPL; Delay_ms(1000);
Beep(880,100); Delay_ms(1000);
//oba pasy
FL; FR; Delay_ms(1000); STOPL; STOPR; Delay_ms(1000);
BL; BR; Delay_ms(1000); STOPL; STOPR; Delay_ms(1000);
};
while (input(DIAG_SENSORS))
{
if (RSENSOR) beep(900,500);
if (LSENSOR) beep(800,500);
if ((read_adc(ADC_READ_ONLY)<BUMPER_TRESHOLD)) beep(1000,500);
};
}
///////////////////////////////////////////////////////////////////////////////
void cikcak()
{
unsigned int16 n;
sem1:
n=CIK_CAK;
while (0==RSENSOR||LSENSOR) // zkontroluj caru
{
if (n==CIK_CAK) // zmen smer zataceni
{
n=0;
switch(movement)
{
case L:
FL;BR;
movement=R;
break;
case R:
FR;BL;
movement=L;
break;
case S:
FL;BR;
movement=R;
n=CIK_CAK/2;
break;
}
}
n++;
}
STOPL;STOPR;
line = RSENSOR; // cteni senzoru na caru
line |= LSENSOR << 1;
if (line==0) goto sem1;
// nasli jsme caru
line=S;
}
///////////////////////////////////////////////////////////////////////////////
void objizdka() // objede cihlu
{
unsigned int16 n;
 
BL;BR;Delay_ms(200);
STOPR;STOPL;
beep(900,1000);
// movement=S;
//cikcak();
 
BL; FR; Delay_ms(215); // otoc se 70° do leva
 
FR; FL; Delay_ms(600); // popojed rovne
 
BR; Delay_ms(50); // otoc se 90° do prava
STOPR; FL; Delay_ms(600);
 
FR; FL; Delay_ms(100); // popojed rovne na slepo
for(n=600;n>0;n--) // popojed rovne ale kontroluj caru
{
line = RSENSOR; // cteni senzoru na caru
line |= LSENSOR << 1;
if (line!=0) {Delay_ms(50); break;} // kdyz narazis na caru, za chvili zastav
Delay_ms(1);
}
 
BL; // otoc se 60° do leva
for(n=600;n>0;n--)
{
line = RSENSOR; // cteni senzoru na caru
line |= LSENSOR << 1;
if (line!=0) break;
Delay_ms(1);
}
STOPR; STOPL;
 
movement=R;
cikcak();
dira=0;
}
///////////////////////////////////////////////////////////////////////////////
void prejeddiru() // vyresi diru
{
unsigned int16 n;
unsigned int8 speed_dira;
 
STOPL;STOPR;
speed_dira=speed;
beep(1000,500);
switch (movement) //vrat se zpet na caru
{
case L:
for (n=COUVANI;n>0;n--) {GO(R,B,speed_dira); Delay_ms(1);}
STOPL;STOPR;
break;
case R:
for (n=COUVANI;n>0;n--) {GO(L,B,speed_dira); Delay_ms(1);}
STOPL;STOPR;
break;
case S:
goto sem;
break;
}
beep(800,500);
 
line=0;
FR; BL; Delay_ms(300); // otoc se na caru
while(line==0)
{
line = RSENSOR; // cteni senzoru na caru
line |= LSENSOR << 1;
}
FL;BR; Delay_ms(60);
STOPL; STOPR;
 
FL; BR; Delay_ms(500);
STOPL; STOPR;
 
Delay_ms(1000);
 
FR;FL; //popojed rovne
for(n=PRES_DIRU;n>0;n--)
{
line = RSENSOR; // cteni senzoru na caru
line |= LSENSOR << 1;
if (line!=0) break;
Delay_ms(1);
}
sem:
STOPL; STOPR;
movement=S;
cikcak(); // najdi caru
dira=0;
}
///////////////////////////////////////////////////////////////////////////////
void main()
{
unsigned int16 n; // pro FOR
 
STOPL; STOPR; // prepne vystupy na ovladani motoru na output a zastavi
 
setup_oscillator(OSC_4MHZ|OSC_INTRC); // 4 MHz interni RC oscilator
 
port_b_pullups(TRUE); // pullups pro piano na diagnostiku
setup_spi(FALSE);
setup_timer_0(RTCC_INTERNAL|RTCC_DIV_1); // Casovac pro PWM
 
setup_timer_2(T2_DIV_BY_4,255,10); // Casovac pro regulaci
// preruseni kazdych 10ms
setup_adc_ports(sAN2|VSS_VDD); // nastaveni A/D prevodniku pro naraznik
setup_adc(ADC_CLOCK_INTERNAL);
set_adc_channel(2);
setup_timer_1(T1_INTERNAL|T1_DIV_BY_1); // Casovac pro naraznik
setup_ccp1(CCP_COMPARE_RESET_TIMER);
CCP_1=(2^10)-1; // prevod kazdou 1ms
 
setup_comparator(A0_VR_A1_VR); // inicializace komparatoru pro cidla cary
setup_vref(VREF_HIGH|TRESHOLD); // 32 kroku od 0.25 do 0.75 Vdd
 
Beep(1000,200); //double beep
Delay_ms(50);
Beep(1000,200);
Delay_ms(1000); // 1s
 
// povoleni rizeni rychlosti zataceni pres preruseni
enable_interrupts(INT_TIMER2);
enable_interrupts(GLOBAL);
 
/*---------------------------------------------------------------------------*/
sensors=S;
line=S;
last=S;
movement=S;
speed=FW_POMALU;
 
diagnostika();
// cikcak(); // toc se, abys nasel caru
Delay_ms(500);
Beep(1000,200);
Delay_ms(500);
 
while(true) // hlavni smycka (jizda podle cary)
{
sensors = RSENSOR; // cteni senzoru na caru
sensors |= LSENSOR << 1;
 
if ((read_adc(ADC_READ_ONLY)<BUMPER_TRESHOLD) && (dira<=T_CIHLA)) objizdka();
 
switch (sensors) // zatacej podle toho, kde vidis caru
{
case S: // rovne
FL; FR; // pokud se jede dlouho rovne, tak pridej
dira=0;
movement=S;
continue;
case L: // trochu vlevo
GO(L, F, FW_POMALU+rovinka); GO(R, F, FW_STREDNE+rovinka);
line=L;
dira=0;
movement=L;
continue;
case R: // trochu vpravo
GO(R, F, FW_POMALU+rovinka); GO(L, F, FW_STREDNE+rovinka);
line=R;
dira=0;
movement=R;
continue;
default: // kdyz jsou obe cidla mimo caru, tak pokracuj dal
}
rovinka=0;
if (dira>=T_DIRA) prejeddiru();
if (last!=line) // pokud si prejel caru z jedne strany na druhou stranu, tak zabrzdi
{
last=line;
speed=FW_ZATACKA;
}
if (L==line) // kdyz jsou obe cidla mimo caru, zatoc na caru
{
STOPL;
GO(R, F, speed);
movement=L;
}
else
{
STOPR;
GO(L, F, speed);
movement=R;
}
} // while(true)
}
 
/roboti/istrobot/merkur/PIC16F88/turn_L/tank.cof
Cannot display: file marked as a binary type.
svn:mime-type = application/octet-stream
Property changes:
Added: svn:mime-type
+application/octet-stream
\ No newline at end of property
/roboti/istrobot/merkur/PIC16F88/turn_L/tank.err
0,0 → 1,0
No Errors
/roboti/istrobot/merkur/PIC16F88/turn_L/tank.h
0,0 → 1,5
#include <16F88.h>
#device adc=8
#fuses NOWDT,INTRC_IO, NOPUT, MCLR, NOBROWNOUT, NOLVP, NOCPD, NOWRT, NODEBUG, NOPROTECT, NOFCMEN, NOIESO
#use delay(clock=4000000)
 
/roboti/istrobot/merkur/PIC16F88/turn_L/tank.sta
0,0 → 1,38
 
ROM used: 1705 (42%)
1705 (42%) including unused fragments
 
2 Average locations per line
4 Average locations per statement
 
RAM used: 87 (50%) at main() level
98 (56%) worst case
 
Lines Stmts % Files
----- ----- --- -----
341 386 85 D:\KAKLIK\programy\PIC_C\roboti\merkur\PIC16F88\turn_L\tank.c
6 0 0 D:\KAKLIK\programy\PIC_C\roboti\merkur\PIC16F88\turn_L\tank.h
275 0 0 C:\Program Files\PICC\devices\16F88.h
136 67 8 D:\KAKLIK\programy\PIC_C\roboti\merkur\PIC16F88\turn_L\AX25.c
----- -----
1516 906 Total
 
Page ROM % RAM Functions:
---- --- --- --- ----------
0 21 1 1 @delay_ms1
0 21 1 1 @delay_us1
0 16 1 0 TIMER2_isr
0 44 3 6 beep
0 352 21 3 diagnostika
0 140 8 3 cikcak
0 247 14 3 objizdka
0 360 21 4 prejeddiru
0 449 26 3 main
 
Segment Used Free
--------- ---- ----
00000-00003 4 0
00004-00036 51 0
00037-007FF 1650 343
00800-00FFF 0 2048
 
/roboti/istrobot/merkur/PIC16F88/turn_L/tank.tre
0,0 → 1,80
ÀÄtank
ÃÄmain 0/449 Ram=3
³ ÃÄ??0??
³ ÃÄbeep 0/44 Ram=6
³ ³ ÃÄ@delay_us1 0/21 Ram=1
³ ³ ÀÄ@delay_us1 0/21 Ram=1
³ ÃÄ@delay_ms1 0/21 Ram=1
³ ÃÄbeep 0/44 Ram=6
³ ³ ÃÄ@delay_us1 0/21 Ram=1
³ ³ ÀÄ@delay_us1 0/21 Ram=1
³ ÃÄ@delay_ms1 0/21 Ram=1
³ ÃÄdiagnostika 0/352 Ram=3
³ ³ ÃÄbeep 0/44 Ram=6
³ ³ ³ ÃÄ@delay_us1 0/21 Ram=1
³ ³ ³ ÀÄ@delay_us1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄbeep 0/44 Ram=6
³ ³ ³ ÃÄ@delay_us1 0/21 Ram=1
³ ³ ³ ÀÄ@delay_us1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄbeep 0/44 Ram=6
³ ³ ³ ÃÄ@delay_us1 0/21 Ram=1
³ ³ ³ ÀÄ@delay_us1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄbeep 0/44 Ram=6
³ ³ ³ ÃÄ@delay_us1 0/21 Ram=1
³ ³ ³ ÀÄ@delay_us1 0/21 Ram=1
³ ³ ÃÄbeep 0/44 Ram=6
³ ³ ³ ÃÄ@delay_us1 0/21 Ram=1
³ ³ ³ ÀÄ@delay_us1 0/21 Ram=1
³ ³ ÀÄbeep 0/44 Ram=6
³ ³ ÃÄ@delay_us1 0/21 Ram=1
³ ³ ÀÄ@delay_us1 0/21 Ram=1
³ ÃÄ@delay_ms1 0/21 Ram=1
³ ÃÄbeep 0/44 Ram=6
³ ³ ÃÄ@delay_us1 0/21 Ram=1
³ ³ ÀÄ@delay_us1 0/21 Ram=1
³ ÃÄ@delay_ms1 0/21 Ram=1
³ ÃÄobjizdka 0/247 Ram=3
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄbeep 0/44 Ram=6
³ ³ ³ ÃÄ@delay_us1 0/21 Ram=1
³ ³ ³ ÀÄ@delay_us1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÀÄcikcak 0/140 Ram=3
³ ÀÄprejeddiru 0/360 Ram=4
³ ÃÄbeep 0/44 Ram=6
³ ³ ÃÄ@delay_us1 0/21 Ram=1
³ ³ ÀÄ@delay_us1 0/21 Ram=1
³ ÃÄ@delay_ms1 0/21 Ram=1
³ ÃÄ@delay_ms1 0/21 Ram=1
³ ÃÄbeep 0/44 Ram=6
³ ³ ÃÄ@delay_us1 0/21 Ram=1
³ ³ ÀÄ@delay_us1 0/21 Ram=1
³ ÃÄ@delay_ms1 0/21 Ram=1
³ ÃÄ@delay_ms1 0/21 Ram=1
³ ÃÄ@delay_ms1 0/21 Ram=1
³ ÃÄ@delay_ms1 0/21 Ram=1
³ ÃÄ@delay_ms1 0/21 Ram=1
³ ÀÄcikcak 0/140 Ram=3
ÀÄTIMER2_isr 0/16 Ram=0
/roboti/istrobot/merkur/PIC16F88/turn_L/verze/1 tank.c
0,0 → 1,313
#include "tank.h"
 
#define TXo PIN_B1 // To the transmitter modulator
#include "AX25.c" // podprogram pro prenos telemetrie
 
//motory //Napred vypnout potom zapnout!
#define FR output_low(PIN_B5); output_high(PIN_B4) // Vpred
#define FL output_low(PIN_B7); output_high(PIN_B6)
#define BR output_low(PIN_B4); output_high(PIN_B5) // Vzad
#define BL output_low(PIN_B6); output_high(PIN_B7)
#define STOPR output_low(PIN_B4);output_low(PIN_B5)
#define STOPL output_low(PIN_B6);output_low(PIN_B7)
 
#define L 0b10 // left
#define R 0b01 // right
#define S 0b11 // straight
 
#define COUVANI 1600 // couvnuti po zjisteni diry
#define MEZERA 5400 // za jak dlouho bude ztracena cara
#define PRES_DIRU 1000 // velikost mezery v care
#define BRZDENI 5000 // doba ptrebna k zastaveni jednoho motoru
 
//cidla
#define RSENSOR C2OUT // Senzory na caru
#define LSENSOR C1OUT
#define BUMPER PIN_A4 // sensor na cihlu
 
#define DIAG_SERVO PIN_B2 // Propojka pro diagnosticky mod
#define DIAG_SENSORS PIN_B3 // Propojka pro diagnosticky mod
 
#DEFINE SOUND_HI PIN_A7
#DEFINE SOUND_LO PIN_A6
 
char AXstring[40]; // Buffer pro prenos telemetrie
 
#define GO(motor, direction, power) if(get_timer0()<=power) \
{direction##motor;} \
else \
{stop##motor;}
 
int movement; // smer minuleho pohybu
int line; // na ktere strane byla detekovana cara
unsigned int16 dira; // pocitadlo pro nalezeni preruseni cary
int speed,speedL,speedR;
 
// Primitivni Pipani
void beep(unsigned int16 period, unsigned int16 length)
{
unsigned int16 nn;
 
for(nn=length; nn>0; nn--)
{
output_high(SOUND_HI);output_low(SOUND_LO);
delay_us(period);
output_high(SOUND_LO);output_low(SOUND_HI);
delay_us(period);
}
}
#int_TIMER2
void TIMER2_isr()
{
switch(line) // upravime smer
{
case S: //obe cidla na care
if(speedL<200)speedL++;
if(speedR<200)speedR++;
break; // vrat se zpet na cteni cidel
case L: // cara je pod levym cidlem, trochu zatocime
if (speedL>100)speedL -- ;
if (speedR<200)speedR ++ ;
break;
case R: // cara pod pravym cidlem
if (speedR>100)speedR -- ;
if (speedL<200)speedL ++ ;
break;
default:
}
}
// Diagnostika pohonu, hejbne vsema motorama ve vsech smerech
void diagnostika()
{
unsigned int16 n;
 
while (input(DIAG_SERVO)) // Propojka, ktera spousti diagnostiku
{
for (n=500; n<800; n+=100)
{
beep(n,n); //beep UP
};
Delay_ms(1000);
//zastav vse
STOPL; STOPR;
//pravy pas
FR; Delay_ms(1000); STOPR; Delay_ms(1000);
BR; Delay_ms(1000); STOPR; Delay_ms(1000);
Beep(880,100); Delay_ms(1000);
//levy pas
FL; Delay_ms(1000); STOPL; Delay_ms(1000);
BL; Delay_ms(1000); STOPL; Delay_ms(1000);
Beep(880,100); Delay_ms(1000);
//oba pasy
FL; FR; Delay_ms(1000); STOPL; STOPR; Delay_ms(1000);
BL; BR; Delay_ms(1000); STOPL; STOPR; Delay_ms(1000);
};
 
while (input(DIAG_SENSORS))
{
int ls, rs;
while(!input(BUMPER)){beep(1100,100); Delay_ms(50);}
set_adc_channel(RSENSOR);
Delay_us(20);
rs=read_adc();
set_adc_channel(LSENSOR);
Delay_us(20);
ls=read_adc();
sprintf(AXstring,"L: %U R: %U\0", ls, rs); // Convert DATA to String.
SendPacket(&AXstring[0]);
delay_ms(1000);
};
}
 
void cikcak()
{
int n;
switch(movement) // podivej se na jednu stranu
{
case L:
FL;BR;
movement=R;
break;
case R:
FR;BL;
movement=L;
break;
case S:
FR;BL;
movement=L;
break;
}
while (0==(RSENSOR|LSENSOR))
{
if (n==50) // asi bude na druhe strane
{
STOPR;STOPL;
n=0;
switch(movement)
{
case L:
FL;BR;
movement=R;
break;
case R:
FR;BL;
movement=L;
break;
}
}
Delay_ms(5);
n++;
}
STOPL;STOPR; // nasli jsme caru
line=S;
}
void objizdka()
{
BL;BR;Delay_ms(300);
STOPR;STOPL;
beep(1000,1000);
Delay_ms(500);
beep(1000,1000);
Delay_ms(1000);
 
 
 
}
 
void pozordira()
{
beep(800,500);
Delay_ms(50);
beep(800,500);
switch (movement) //vrat se zpet na caru
{
case L:
STOPL;STOPR;
BR;Delay_ms(COUVANI);STOPR;
break;
case R:
STOPL;STOPR;
BL;Delay_ms(COUVANI);STOPL;
break;
case S:
BL; BR; Delay_ms(COUVANI);
STOPL; STOPR;
break;
}
 
FR;FL; Delay_ms(PRES_DIRU); // popojedem dopredu mozna tam bude cara
STOPL; STOPR; movement=S;
cikcak(); // najdi caru
dira=0;
}
 
void main()
{
unsigned int16 rovinka;
int last;
 
STOPL; STOPR;
 
setup_oscillator(OSC_4MHZ|OSC_INTRC); // 4 MHz interni RC oscilator
port_b_pullups(true);
setup_adc_ports(NO_ANALOGS|VSS_VDD);
setup_adc(ADC_OFF);
setup_spi(FALSE);
setup_timer_0(RTCC_INTERNAL|RTCC_DIV_1); // Casovac pro PWM
setup_timer_1(T1_DISABLED); // Casovac pro regulaci
setup_timer_2(T2_DIV_BY_16,50,16);
setup_ccp1(CCP_OFF);
setup_comparator(A0_VR_A1_VR);
setup_vref(VREF_HIGH|15);
enable_interrupts(INT_TIMER2);
enable_interrupts(GLOBAL);
 
diagnostika();
 
Beep(1000,200); //double beep
Delay_ms(50);
Beep(1000,200);
Delay_ms(1000); // 1s
 
// FL; FR;
movement=S;
line=S;
dira=0;
last=0;
rovinka=0;
 
speed=speedL=speedR=200;
 
while(true)
{
line = RSENSOR; // precteni cidel
line |= LSENSOR << 1; // sestav informaci o care
if(line!=0)
{
GO(L, F, speedL); GO(R,F, speedR);
}
else{STOPR; STOPL;}
//sem:
/* switch(line) // upravime smer
{
case S: //obe cidla na care
// if (speedL<speedR) speedL=speedR;
// else speedR=speedL;
GO(L,F,speedL); GO(R,F,speedR) // jedeme rovne
// if(rovinka<BRZDENI) rovinka++; //cara je rovne
// dira=0; // videli jsme caru, proto neni dira
continue; // vrat se zpet na cteni cidel
case L: // cara je pod levym cidlem, trochu zatocime
GO(L, F, speedL); GO(R,F, speedR);
// if(rovinka<BRZDENI) rovinka++; //cara je celkem rovne
// dira=0;
continue;
case R: // cara pod pravym cidlem
GO(R, F, speedR); GO(L, F, speedL);
// if(rovinka<BRZDENI) rovinka++;
// dira=0;
continue;
default: // cara neni pod zadnym cidlem
}*/
 
 
/*switch (last) // zatacka
{
case L: // do leva
BL;STOPR; //zabrzdeni leveho motoru
for(;rovinka>0;rovinka--) //chvili pockej
{
line = RSENSOR; // precteni cidel
line |= LSENSOR << 1; // sestav informaci o care
if(line!=0) goto sem; //kdyz najdes caru, zastav
}
STOPL; FR; // pokracuj v zataceni
while(line==0)
{
line = RSENSOR; // precteni cidel
line |= LSENSOR << 1; // sestav informaci o care
}
movement=L;
rovinka=0; //zataceli jsme, uz neni rovna cara
break;
case R:
BR; STOPL; // zabrzdeni praveho motoru
for(;rovinka>0;rovinka--)
{
line = RSENSOR; // precteni cidel
line |= LSENSOR << 1; // sestav informaci o care
if(line!=0) goto sem;
}
STOPR; FL;
while(line==0)
{
line = RSENSOR; // precteni cidel
line |= LSENSOR << 1; // sestav informaci o care
}
movement=R;
rovinka=0; //zataceli jsme, uz neni rovna cara
break;
}*/
} // while(true)
}
/roboti/istrobot/merkur/PIC16F88/turn_L/verze/2 tank.c
0,0 → 1,331
#include "tank.h"
 
#define DEBUG
 
#define TXo PIN_A3 // To the transmitter modulator
#include "AX25.c" // podprogram pro prenos telemetrie
 
unsigned int8 sensors; // pomocna promenna pro cteni cidel na caru
unsigned int8 line; // na ktere strane byla detekovana cara
unsigned int8 speed; // rychlost zataceni
unsigned int8 rovinka; // pocitadlo pro zjisteni rovneho useku
unsigned int8 last; // kde byla cara, kdyz byly minule cidla mimo
unsigned int8 movement; // obsahuje aktualni smer zataceni
unsigned int8 dira; // pocita dobu po kterou je ztracena cara
 
// Konstanty pro dynamiku pohybu
#define T_DIRA 100 // po jakem case zataceni se detekuje dira
#define INC_SPEED 1 // prirustek rychlosti v jednom kroku
#define FW_POMALU 100 // trochu mimo caru vnitrni pas
#define FW_ZATACKA 200 // rychlost vnejsiho kola pri zataceni
#define FW_STREDNE 110 // trochu mimo caru vnejsi pas
#define COUVANI 600 // couvnuti zpet na caru, po detekci diry
#define PRES_DIRU 300
#define MAX_ROVINKA (255-FW_STREDNE)
#define TRESHOLD 6 // rozhodovaci uroven komparatoru, 0xF = 0.75*Vdd
 
//motory //Napred vypnout potom zapnout!
#define FR output_low(PIN_B5); output_high(PIN_B4) // Vpred
#define FL output_low(PIN_B7); output_high(PIN_B6)
#define BR output_low(PIN_B4); output_high(PIN_B5) // Vzad
#define BL output_low(PIN_B6); output_high(PIN_B7)
#define STOPR output_low(PIN_B4);output_low(PIN_B5) // Zastav
#define STOPL output_low(PIN_B6);output_low(PIN_B7)
 
#define L 0b10 // left
#define R 0b01 // right
#define S 0b11 // straight
 
//cidla
#define RSENSOR C2OUT // Senzory na caru
#define LSENSOR C1OUT
#define BUMPER PIN_A4 // Senzor na cihlu
 
#define DIAG_SERVO PIN_B3 // Propojka pro diagnosticky mod
#define DIAG_SENSORS PIN_B2 // Propojka pro diagnosticky mod
 
#DEFINE SOUND_HI PIN_A6 // komplementarni vystupy pro piezo pipak
#DEFINE SOUND_LO PIN_A7
 
char AXstring[40]; // Buffer pro prenos telemetrie
 
// makro pro PWM
#define GO(motor, direction, power) if(get_timer0()<=power) \
{direction##motor;} \
else \
{stop##motor;}
 
#int_TIMER2
void TIMER2_isr()
{
if (speed<255) speed+=INC_SPEED;
if (rovinka<MAX_ROVINKA) rovinka++;
if (dira<T_DIRA) dira++;
}
 
// Primitivni Pipani
void beep(unsigned int16 period, unsigned int16 length)
{
unsigned int16 nn;
 
for(nn=length; nn>0; nn--)
{
output_high(SOUND_HI);output_low(SOUND_LO);
delay_us(period);
output_high(SOUND_LO);output_low(SOUND_HI);
delay_us(period);
}
}
/******************************************************************************/
void diagnostika()
{
unsigned int16 n;
 
while (input(DIAG_SERVO)) // Propojka, ktera spousti diagnostiku
{
for (n=500; n<800; n+=100)
{
beep(n,n); //beep UP
};
Delay_ms(1000);
//zastav vse
STOPL; STOPR;
//pravy pas
FR; Delay_ms(1000); STOPR; Delay_ms(1000);
BR; Delay_ms(1000); STOPR; Delay_ms(1000);
Beep(880,100); Delay_ms(1000);
//levy pas
FL; Delay_ms(1000); STOPL; Delay_ms(1000);
BL; Delay_ms(1000); STOPL; Delay_ms(1000);
Beep(880,100); Delay_ms(1000);
//oba pasy
FL; FR; Delay_ms(1000); STOPL; STOPR; Delay_ms(1000);
BL; BR; Delay_ms(1000); STOPL; STOPR; Delay_ms(1000);
};
 
while (input(DIAG_SENSORS))
{
int ls, rs;
while(!input(BUMPER)){beep(1100,100); Delay_ms(50);}
set_adc_channel(RSENSOR);
Delay_us(20);
rs=read_adc();
set_adc_channel(LSENSOR);
Delay_us(20);
ls=read_adc();
sprintf(AXstring,"L: %U R: %U\0", ls, rs); // Convert DATA to String.
SendPacket(&AXstring[0]);
delay_ms(1000);
};
}
///////////////////////////////////////////////////////////////////////////////
void cikcak()
{
int n;
switch(movement) // podivej se na jednu stranu
{
case L:
FL;BR;
movement=R;
break;
case R:
FR;BL;
movement=L;
break;
case S:
FR;BL;
movement=L;
break;
}
while (0==(RSENSOR|LSENSOR))
{
if (n==50) //cara asi bude na druhe strane
{
STOPR;STOPL;
n=0;
switch(movement)
{
case L:
FL;BR;
movement=R;
break;
case R:
FR;BL;
movement=L;
break;
}
}
Delay_ms(5);
n++;
}
STOPL;STOPR; // nasli jsme caru
line=S;
}
///////////////////////////////////////////////////////////////////////////////
void objizdka()
{
BL;BR;Delay_ms(300);
STOPR;STOPL;
beep(1000,1000);
Delay_ms(500);
beep(1000,1000);
Delay_ms(1000);
 
 
 
}
///////////////////////////////////////////////////////////////////////////////
void prejeddiru()
{
STOPL;STOPR;
beep(800,500);
Delay_ms(50);
beep(800,500);
switch (movement) //vrat se zpet na caru
{
case L:
BR;Delay_ms(COUVANI);STOPR;
STOPL;STOPR;
break;
case R:
 
BL;Delay_ms(COUVANI);STOPL;
STOPL;STOPR;
break;
case S:
BL; BR; Delay_ms(COUVANI);
STOPL; STOPR;
break;
}
 
FR;FL; Delay_ms(PRES_DIRU); // popojedem dopredu mozna tam bude cara
STOPL; STOPR;
cikcak(); // najdi caru
dira=0;
}
///////////////////////////////////////////////////////////////////////////////
void main()
{
unsigned int16 n; // pro FOR
 
STOPL; STOPR; // prepne vystupy na ovladani motoru na output a zastavi
 
setup_oscillator(OSC_4MHZ|OSC_INTRC); // 4 MHz interni RC oscilator
 
port_b_pullups(TRUE); // pullups pro piano na diagnostiku
setup_spi(FALSE);
setup_timer_0(RTCC_INTERNAL|RTCC_DIV_1); // Casovac pro PWM
 
setup_timer_2(T2_DIV_BY_16,255,10); // Casovac pro regulaci
// preruseni kazdych 10ms
setup_adc_ports(sAN2|VSS_VDD); // nastaveni A/D prevodniku pro naraznik
setup_adc(ADC_CLOCK_INTERNAL);
set_adc_channel(2);
setup_timer_1(T1_INTERNAL|T1_DIV_BY_1); // Casovac pro naraznik
setup_ccp1(CCP_COMPARE_RESET_TIMER);
CCP_1=(2^10)-1; // prevod kazdou 1ms
 
setup_comparator(A0_VR_A1_VR); // inicializace komparatoru pro cidla cary
setup_vref(VREF_HIGH|TRESHOLD); // 32 kroku od 0.25 do 0.75 Vdd
 
Beep(1000,200); //double beep
Delay_ms(50);
Beep(1000,200);
Delay_ms(1000); // 1s
 
// povoleni rizeni rychlosti zataceni pres preruseni
enable_interrupts(INT_TIMER2);
enable_interrupts(GLOBAL);
 
/*---------------------------------------------------------------------------*/
sensors=S;
line=S;
last=S;
movement=S;
speed=FW_POMALU;
 
diagnostika();
cikcak(); // toc se, abys nasel caru
Delay_ms(500);
Beep(1000,200);
Delay_ms(500);
 
while(true) // hlavni smycka (jizda podle cary)
{
 
sensors = RSENSOR; // cteni senzoru na caru
sensors |= LSENSOR << 1;
 
switch (sensors) // zatacej podle toho, kde vidis caru
{
case S: // rovne
GO(L, F, speed); GO(R, F, speed);
// FL; FR; // pokud se jede dlouho rovne, tak pridej
dira=0;
continue;
 
case L: // trochu vlevo
GO(L, F, FW_POMALU+rovinka); GO(R, F, FW_STREDNE+rovinka);
line=L;
dira=0;
continue;
 
case R: // trochu vpravo
GO(R, F, FW_POMALU+rovinka); GO(L, F, FW_STREDNE+rovinka);
line=R;
dira=0;
continue;
 
default: // kdyz jsou obe cidla mimo caru, tak pokracuj dal
}
rovinka=0;
// if (dira>=T_DIRA) prejeddiru();
if (last!=line) // pokud si prejel caru z jedne strany na druhou stranu, tak zabrzdi
{
last=line;
speed=FW_ZATACKA;
}
else speed=255;
/* if (dira==0)
{
if (L==line) // kdyz jsou obe cidla mimo caru, zabrzdi vnitrni kolo
{
BL;
for(n=4000;n>0;n--) // Delay
{
line = RSENSOR; // precteni cidel
line |= LSENSOR << 1; // sestav informaci o care
if(line!=0) break;
}
STOPL;
}
else
{
BR;
for(n=4000;n>0;n--) // Delay
{
line = RSENSOR; // precteni cidel
line |= LSENSOR << 1; // sestav informaci o care
if(line!=0) break;
}
STOPR;
}
}*/
if (L==line) // kdyz jsou obe cidla mimo caru, zatoc na caru
{
STOPL;
GO(R, F, speed);
movement=L;
}
else
{
STOPR;
GO(L, F, speed);
movement=R;
}
} // while(true)
}
 
/roboti/istrobot/merkur/PIC16F88/turn_L/verze/tank_funkcni.BAK
0,0 → 1,352
#include "tank.h"
 
#define DEBUG
 
#define TXo PIN_A3 // To the transmitter modulator
#include "AX25.c" // podprogram pro prenos telemetrie
 
unsigned int8 sensors; // pomocna promenna pro cteni cidel na caru
unsigned int8 line; // na ktere strane byla detekovana cara
unsigned int8 speed; // rychlost zataceni
unsigned int8 rovinka; // pocitadlo pro zjisteni rovneho useku
unsigned int8 last; // kde byla cara, kdyz byly minule cidla mimo
unsigned int8 movement; // obsahuje aktualni smer zataceni
unsigned int8 dira; // pocita dobu po kterou je ztracena cara
unsigned int8 cihla; // urcuje za jak dlouho muze byt znova detekovana cihla
 
// Konstanty pro dynamiku pohybu
#define T_DIRA 87 // po jakem case zataceni se detekuje dira
#define INC_SPEED 1 // prirustek rychlosti v jednom kroku
#define FW_POMALU 230 // trochu mimo caru vnitrni pas
#define FW_ZATACKA 200 // rychlost vnejsiho kola pri zataceni
#define FW_STREDNE 240 // trochu mimo caru vnejsi pas
#define COUVANI 600 // couvnuti zpet na caru, po detekci diry
#define PRES_DIRU 250
#define MAX_ROVINKA (255-FW_STREDNE)
#define TRESHOLD 10 // rozhodovaci uroven komparatoru, 0xF = 0.75*Vdd
#define BUMPER_TRESHOLD 128
#define CIK_CAK 30000
#define T_CIHLA 100 // perioda detekce cihly
 
//motory //Napred vypnout potom zapnout!
#define FR output_low(PIN_B5); output_high(PIN_B4) // Vpred
#define FL output_low(PIN_B7); output_high(PIN_B6)
#define BR output_low(PIN_B4); output_high(PIN_B5) // Vzad
#define BL output_low(PIN_B6); output_high(PIN_B7)
#define STOPR output_low(PIN_B4);output_low(PIN_B5) // Zastav
#define STOPL output_low(PIN_B6);output_low(PIN_B7)
 
#define L 0b10 // left
#define R 0b01 // right
#define S 0b11 // straight
 
//cidla
#define RSENSOR C2OUT // Senzory na caru
#define LSENSOR C1OUT
#define BUMPER PIN_A4 // Senzor na cihlu
 
#define DIAG_SERVO PIN_B3 // Propojka pro diagnosticky mod
#define DIAG_SENSORS PIN_B2 // Propojka pro diagnosticky mod
 
#DEFINE SOUND_HI PIN_A6 // komplementarni vystupy pro piezo pipak
#DEFINE SOUND_LO PIN_A7
 
char AXstring[40]; // Buffer pro prenos telemetrie
 
// makro pro PWM
#define GO(motor, direction, power) if(get_timer0()<=power) \
{direction##motor;} else {stop##motor;}
 
#int_TIMER2
void TIMER2_isr()
{
if (speed<255) speed+=INC_SPEED;
if (rovinka<MAX_ROVINKA) rovinka++;
if (dira<=T_DIRA) dira++;
if (cihla>0) cihla--;
}
// Primitivni Pipani
void beep(unsigned int16 period, unsigned int16 length)
{
unsigned int16 nn;
 
for(nn=length; nn>0; nn--)
{
output_high(SOUND_HI);output_low(SOUND_LO);
delay_us(period);
output_high(SOUND_LO);output_low(SOUND_HI);
delay_us(period);
}
}
/******************************************************************************/
void diagnostika()
{
unsigned int16 n;
 
while (input(DIAG_SERVO)) // Propojka, ktera spousti diagnostiku
{
for (n=500; n<800; n+=100)
{
beep(n,n); //beep UP
};
Delay_ms(1000);
//zastav vse
STOPL; STOPR;
//pravy pas
FR; Delay_ms(1000); STOPR; Delay_ms(1000);
BR; Delay_ms(1000); STOPR; Delay_ms(1000);
Beep(880,100); Delay_ms(1000);
//levy pas
FL; Delay_ms(1000); STOPL; Delay_ms(1000);
BL; Delay_ms(1000); STOPL; Delay_ms(1000);
Beep(880,100); Delay_ms(1000);
//oba pasy
FL; FR; Delay_ms(1000); STOPL; STOPR; Delay_ms(1000);
BL; BR; Delay_ms(1000); STOPL; STOPR; Delay_ms(1000);
};
while (input(DIAG_SENSORS))
{
int ls, rs;
while(!input(BUMPER)){beep(1100,100); Delay_ms(50);}
set_adc_channel(RSENSOR);
Delay_us(20);
rs=read_adc();
set_adc_channel(LSENSOR);
Delay_us(20);
ls=read_adc();
sprintf(AXstring,"L: %U R: %U\0", ls, rs); // Convert DATA to String.
SendPacket(&AXstring[0]);
delay_ms(1000);
};
}
///////////////////////////////////////////////////////////////////////////////
void cikcak()
{
unsigned int16 n;
sem1:
n=CIK_CAK;
while (0==RSENSOR) // zkontroluj caru
{
if (n==CIK_CAK) // zmen smer zataceni
{
n=0;
switch(movement)
{
case L:
FL;BR;
movement=R;
break;
case R:
FR;BL;
movement=L;
break;
case S:
FL;BR;
movement=R;
n=CIK_CAK/2;
break;
}
}
n++;
}
STOPL;STOPR;
line = RSENSOR; // cteni senzoru na caru
line |= LSENSOR << 1;
if (line==0) goto sem1;
// nasli jsme caru
line=S;
}
///////////////////////////////////////////////////////////////////////////////
void objizdka() // objede cihlu
{
unsigned int16 n;
 
BL;BR;Delay_ms(200);
STOPR;STOPL;
beep(900,1000);
// movement=S;
// cikcak();
 
BR; FL; Delay_ms(215); // otoc se 70° do prava
 
FR; FL; Delay_ms(600); // popojed rovne
 
BL; Delay_ms(30); // otoc se 90° do leva
STOPL; FR; Delay_ms(600);
 
FR; FL; Delay_ms(100); // popojed rovne na slepo
for(n=600;n>0;n--) // popojed rovne ale kontroluj caru
{
line = RSENSOR; // cteni senzoru na caru
line |= LSENSOR << 1;
if (line!=0) {Delay_ms(50); break;}
Delay_ms(1);
}
 
BR; // otoc se 60° do prava
for(n=600;n>0;n--)
{
line = RSENSOR; // cteni senzoru na caru
line |= LSENSOR << 1;
if (line!=0) break;
Delay_ms(1);
}
STOPR; STOPL;
 
movement=R;
cikcak();
cihla=T_CIHLA;
dira=0;
}
///////////////////////////////////////////////////////////////////////////////
void prejeddiru() // vyresi diru
{
unsigned int16 n;
unsigned int8 speed_dira;
 
STOPL;STOPR;
speed_dira=speed;
beep(1000,500);
switch (movement) //vrat se zpet na caru
{
case L:
for (n=COUVANI;n>0;n--) {GO(R,B,speed_dira); Delay_ms(1);}
STOPL;STOPR;
break;
case R:
for (n=COUVANI;n>0;n--) {GO(L,B,speed_dira); Delay_ms(1);}
STOPL;STOPR;
break;
case S:
goto sem;
break;
}
beep(800,500);
line=0;
FR; BL; Delay_ms(300); // otoc se na caru
while(line==0)
{
line = RSENSOR; // cteni senzoru na caru
line |= LSENSOR << 1;
}
FL;BR; Delay_ms(60);
STOPL; STOPR;
FL; BR; Delay_ms(500);
STOPL; STOPR;
Delay_ms(1000);
FR;FL; //popojed rovne
for(n=PRES_DIRU;n>0;n--)
{
line = RSENSOR; // cteni senzoru na caru
line |= LSENSOR << 1;
if (line!=0) break;
Delay_ms(1);
}
sem:
STOPL; STOPR;
movement=S;
cikcak(); // najdi caru
cihla=T_CIHLA;
dira=0;
}
///////////////////////////////////////////////////////////////////////////////
void main()
{
unsigned int16 n; // pro FOR
 
STOPL; STOPR; // prepne vystupy na ovladani motoru na output a zastavi
 
setup_oscillator(OSC_4MHZ|OSC_INTRC); // 4 MHz interni RC oscilator
 
port_b_pullups(TRUE); // pullups pro piano na diagnostiku
setup_spi(FALSE);
setup_timer_0(RTCC_INTERNAL|RTCC_DIV_1); // Casovac pro PWM
 
setup_timer_2(T2_DIV_BY_4,255,10); // Casovac pro regulaci
// preruseni kazdych 10ms
setup_adc_ports(sAN2|VSS_VDD); // nastaveni A/D prevodniku pro naraznik
setup_adc(ADC_CLOCK_INTERNAL);
set_adc_channel(2);
setup_timer_1(T1_INTERNAL|T1_DIV_BY_1); // Casovac pro naraznik
setup_ccp1(CCP_COMPARE_RESET_TIMER);
CCP_1=(2^10)-1; // prevod kazdou 1ms
 
setup_comparator(A0_VR_A1_VR); // inicializace komparatoru pro cidla cary
setup_vref(VREF_HIGH|TRESHOLD); // 32 kroku od 0.25 do 0.75 Vdd
 
Beep(1000,200); //double beep
Delay_ms(50);
Beep(1000,200);
Delay_ms(1000); // 1s
 
// povoleni rizeni rychlosti zataceni pres preruseni
enable_interrupts(INT_TIMER2);
enable_interrupts(GLOBAL);
 
/*---------------------------------------------------------------------------*/
sensors=S;
line=S;
last=S;
movement=S;
speed=FW_POMALU;
 
diagnostika();
// cikcak(); // toc se, abys nasel caru
Delay_ms(500);
Beep(1000,200);
Delay_ms(500);
 
while(true) // hlavni smycka (jizda podle cary)
{
sensors = RSENSOR; // cteni senzoru na caru
sensors |= LSENSOR << 1;
 
if ((read_adc(ADC_READ_ONLY)<BUMPER_TRESHOLD) && (cihla==0)) objizdka();
 
switch (sensors) // zatacej podle toho, kde vidis caru
{
case S: // rovne
FL; FR; // pokud se jede dlouho rovne, tak pridej
dira=0;
movement=S;
continue;
case L: // trochu vlevo
GO(L, F, FW_POMALU+rovinka); GO(R, F, FW_STREDNE+rovinka);
line=L;
dira=0;
movement=L;
continue;
case R: // trochu vpravo
GO(R, F, FW_POMALU+rovinka); GO(L, F, FW_STREDNE+rovinka);
line=R;
dira=0;
movement=R;
continue;
default: // kdyz jsou obe cidla mimo caru, tak pokracuj dal
}
rovinka=0;
if (dira>=T_DIRA) prejeddiru();
if (last!=line) // pokud si prejel caru z jedne strany na druhou stranu, tak zabrzdi
{
last=line;
speed=FW_ZATACKA;
}
if (L==line) // kdyz jsou obe cidla mimo caru, zatoc na caru
{
STOPL;
GO(R, F, speed);
movement=L;
}
else
{
STOPR;
GO(L, F, speed);
movement=R;
}
} // while(true)
}
 
/roboti/istrobot/merkur/PIC16F88/turn_L/verze/tank_funkcni.c
0,0 → 1,352
#include "tank.h"
 
#define DEBUG
 
#define TXo PIN_A3 // To the transmitter modulator
#include "AX25.c" // podprogram pro prenos telemetrie
 
unsigned int8 sensors; // pomocna promenna pro cteni cidel na caru
unsigned int8 line; // na ktere strane byla detekovana cara
unsigned int8 speed; // rychlost zataceni
unsigned int8 rovinka; // pocitadlo pro zjisteni rovneho useku
unsigned int8 last; // kde byla cara, kdyz byly minule cidla mimo
unsigned int8 movement; // obsahuje aktualni smer zataceni
unsigned int8 dira; // pocita dobu po kterou je ztracena cara
unsigned int8 cihla; // urcuje za jak dlouho muze byt znova detekovana cihla
 
// Konstanty pro dynamiku pohybu
#define T_DIRA 87 // po jakem case zataceni se detekuje dira
#define INC_SPEED 1 // prirustek rychlosti v jednom kroku
#define FW_POMALU 230 // trochu mimo caru vnitrni pas
#define FW_ZATACKA 200 // rychlost vnejsiho kola pri zataceni
#define FW_STREDNE 240 // trochu mimo caru vnejsi pas
#define COUVANI 600 // couvnuti zpet na caru, po detekci diry
#define PRES_DIRU 250
#define MAX_ROVINKA (255-FW_STREDNE)
#define TRESHOLD 10 // rozhodovaci uroven komparatoru, 0xF = 0.75*Vdd
#define BUMPER_TRESHOLD 128
#define CIK_CAK 30000
#define T_CIHLA 100 // perioda detekce cihly
 
//motory //Napred vypnout potom zapnout!
#define FR output_low(PIN_B5); output_high(PIN_B4) // Vpred
#define FL output_low(PIN_B7); output_high(PIN_B6)
#define BR output_low(PIN_B4); output_high(PIN_B5) // Vzad
#define BL output_low(PIN_B6); output_high(PIN_B7)
#define STOPR output_low(PIN_B4);output_low(PIN_B5) // Zastav
#define STOPL output_low(PIN_B6);output_low(PIN_B7)
 
#define L 0b10 // left
#define R 0b01 // right
#define S 0b11 // straight
 
//cidla
#define RSENSOR C2OUT // Senzory na caru
#define LSENSOR C1OUT
#define BUMPER PIN_A4 // Senzor na cihlu
 
#define DIAG_SERVO PIN_B3 // Propojka pro diagnosticky mod
#define DIAG_SENSORS PIN_B2 // Propojka pro diagnosticky mod
 
#DEFINE SOUND_HI PIN_A6 // komplementarni vystupy pro piezo pipak
#DEFINE SOUND_LO PIN_A7
 
char AXstring[40]; // Buffer pro prenos telemetrie
 
// makro pro PWM
#define GO(motor, direction, power) if(get_timer0()<=power) \
{direction##motor;} else {stop##motor;}
 
#int_TIMER2
void TIMER2_isr()
{
if (speed<255) speed+=INC_SPEED;
if (rovinka<MAX_ROVINKA) rovinka++;
if (dira<=T_DIRA) dira++;
if (cihla>0) cihla--;
}
// Primitivni Pipani
void beep(unsigned int16 period, unsigned int16 length)
{
unsigned int16 nn;
 
for(nn=length; nn>0; nn--)
{
output_high(SOUND_HI);output_low(SOUND_LO);
delay_us(period);
output_high(SOUND_LO);output_low(SOUND_HI);
delay_us(period);
}
}
/******************************************************************************/
void diagnostika()
{
unsigned int16 n;
 
while (input(DIAG_SERVO)) // Propojka, ktera spousti diagnostiku
{
for (n=500; n<800; n+=100)
{
beep(n,n); //beep UP
};
Delay_ms(1000);
//zastav vse
STOPL; STOPR;
//pravy pas
FR; Delay_ms(1000); STOPR; Delay_ms(1000);
BR; Delay_ms(1000); STOPR; Delay_ms(1000);
Beep(880,100); Delay_ms(1000);
//levy pas
FL; Delay_ms(1000); STOPL; Delay_ms(1000);
BL; Delay_ms(1000); STOPL; Delay_ms(1000);
Beep(880,100); Delay_ms(1000);
//oba pasy
FL; FR; Delay_ms(1000); STOPL; STOPR; Delay_ms(1000);
BL; BR; Delay_ms(1000); STOPL; STOPR; Delay_ms(1000);
};
while (input(DIAG_SENSORS))
{
int ls, rs;
while(!input(BUMPER)){beep(1100,100); Delay_ms(50);}
set_adc_channel(RSENSOR);
Delay_us(20);
rs=read_adc();
set_adc_channel(LSENSOR);
Delay_us(20);
ls=read_adc();
sprintf(AXstring,"L: %U R: %U\0", ls, rs); // Convert DATA to String.
SendPacket(&AXstring[0]);
delay_ms(1000);
};
}
///////////////////////////////////////////////////////////////////////////////
void cikcak()
{
unsigned int16 n;
sem1:
n=CIK_CAK;
while (0==RSENSOR) // zkontroluj caru
{
if (n==CIK_CAK) // zmen smer zataceni
{
n=0;
switch(movement)
{
case L:
FL;BR;
movement=R;
break;
case R:
FR;BL;
movement=L;
break;
case S:
FL;BR;
movement=R;
n=CIK_CAK/2;
break;
}
}
n++;
}
STOPL;STOPR;
line = RSENSOR; // cteni senzoru na caru
line |= LSENSOR << 1;
if (line==0) goto sem1;
// nasli jsme caru
line=S;
}
///////////////////////////////////////////////////////////////////////////////
void objizdka() // objede cihlu
{
unsigned int16 n;
 
BL;BR;Delay_ms(200);
STOPR;STOPL;
beep(900,1000);
// movement=S;
// cikcak();
 
BR; FL; Delay_ms(215); // otoc se 70° do prava
 
FR; FL; Delay_ms(600); // popojed rovne
 
BL; Delay_ms(30); // otoc se 90° do leva
STOPL; FR; Delay_ms(600);
 
FR; FL; Delay_ms(100); // popojed rovne na slepo
for(n=600;n>0;n--) // popojed rovne ale kontroluj caru
{
line = RSENSOR; // cteni senzoru na caru
line |= LSENSOR << 1;
if (line!=0) {Delay_ms(50); break;}
Delay_ms(1);
}
 
BR; // otoc se 60° do prava
for(n=600;n>0;n--)
{
line = RSENSOR; // cteni senzoru na caru
line |= LSENSOR << 1;
if (line!=0) break;
Delay_ms(1);
}
STOPR; STOPL;
 
movement=R;
cikcak();
cihla=T_CIHLA;
dira=0;
}
///////////////////////////////////////////////////////////////////////////////
void prejeddiru() // vyresi diru
{
unsigned int16 n;
unsigned int8 speed_dira;
 
STOPL;STOPR;
speed_dira=speed;
beep(1000,500);
switch (movement) //vrat se zpet na caru
{
case L:
for (n=COUVANI;n>0;n--) {GO(R,B,speed_dira); Delay_ms(1);}
STOPL;STOPR;
break;
case R:
for (n=COUVANI;n>0;n--) {GO(L,B,speed_dira); Delay_ms(1);}
STOPL;STOPR;
break;
case S:
goto sem;
break;
}
beep(800,500);
line=0;
FR; BL; Delay_ms(300); // otoc se na caru
while(line==0)
{
line = RSENSOR; // cteni senzoru na caru
line |= LSENSOR << 1;
}
FL;BR; Delay_ms(60);
STOPL; STOPR;
FL; BR; Delay_ms(500);
STOPL; STOPR;
Delay_ms(1000);
FR;FL; //popojed rovne
for(n=PRES_DIRU;n>0;n--)
{
line = RSENSOR; // cteni senzoru na caru
line |= LSENSOR << 1;
if (line!=0) break;
Delay_ms(1);
}
sem:
STOPL; STOPR;
movement=S;
cikcak(); // najdi caru
cihla=T_CIHLA;
dira=0;
}
///////////////////////////////////////////////////////////////////////////////
void main()
{
unsigned int16 n; // pro FOR
 
STOPL; STOPR; // prepne vystupy na ovladani motoru na output a zastavi
 
setup_oscillator(OSC_4MHZ|OSC_INTRC); // 4 MHz interni RC oscilator
 
port_b_pullups(TRUE); // pullups pro piano na diagnostiku
setup_spi(FALSE);
setup_timer_0(RTCC_INTERNAL|RTCC_DIV_1); // Casovac pro PWM
 
setup_timer_2(T2_DIV_BY_4,255,10); // Casovac pro regulaci
// preruseni kazdych 10ms
setup_adc_ports(sAN2|VSS_VDD); // nastaveni A/D prevodniku pro naraznik
setup_adc(ADC_CLOCK_INTERNAL);
set_adc_channel(2);
setup_timer_1(T1_INTERNAL|T1_DIV_BY_1); // Casovac pro naraznik
setup_ccp1(CCP_COMPARE_RESET_TIMER);
CCP_1=(2^10)-1; // prevod kazdou 1ms
 
setup_comparator(A0_VR_A1_VR); // inicializace komparatoru pro cidla cary
setup_vref(VREF_HIGH|TRESHOLD); // 32 kroku od 0.25 do 0.75 Vdd
 
Beep(1000,200); //double beep
Delay_ms(50);
Beep(1000,200);
Delay_ms(1000); // 1s
 
// povoleni rizeni rychlosti zataceni pres preruseni
enable_interrupts(INT_TIMER2);
enable_interrupts(GLOBAL);
 
/*---------------------------------------------------------------------------*/
sensors=S;
line=S;
last=S;
movement=S;
speed=FW_POMALU;
 
diagnostika();
// cikcak(); // toc se, abys nasel caru
Delay_ms(500);
Beep(1000,200);
Delay_ms(500);
 
while(true) // hlavni smycka (jizda podle cary)
{
sensors = RSENSOR; // cteni senzoru na caru
sensors |= LSENSOR << 1;
 
if ((read_adc(ADC_READ_ONLY)<BUMPER_TRESHOLD) && (cihla==0)) objizdka();
 
switch (sensors) // zatacej podle toho, kde vidis caru
{
case S: // rovne
FL; FR; // pokud se jede dlouho rovne, tak pridej
dira=0;
movement=S;
continue;
case L: // trochu vlevo
GO(L, F, FW_POMALU+rovinka); GO(R, F, FW_STREDNE+rovinka);
line=L;
dira=0;
movement=L;
continue;
case R: // trochu vpravo
GO(R, F, FW_POMALU+rovinka); GO(L, F, FW_STREDNE+rovinka);
line=R;
dira=0;
movement=R;
continue;
default: // kdyz jsou obe cidla mimo caru, tak pokracuj dal
}
rovinka=0;
if (dira>=T_DIRA) prejeddiru();
if (last!=line) // pokud si prejel caru z jedne strany na druhou stranu, tak zabrzdi
{
last=line;
speed=FW_ZATACKA;
}
if (L==line) // kdyz jsou obe cidla mimo caru, zatoc na caru
{
STOPL;
GO(R, F, speed);
movement=L;
}
else
{
STOPR;
GO(L, F, speed);
movement=R;
}
} // while(true)
}
 
/roboti/istrobot/merkur/PIC16F88/turn_R/AX25.c
0,0 → 1,135
#nolist
//#define PTT PIN_A2 // PTT control
//#define TXo PIN_C0 // To the transmitter modulator
#define PERIODAH delay_us(222) // Halfperiod H 222;78/1200 500;430/500
#define TAILH delay_us(78)
#define PERIODAL delay_us(412) // Halfperiod L 412;345/1200 1000;880/500
#define TAILL delay_us(345)
#byte STATUS = 3 // CPUs status register
 
byte SendData[16] = {'A'<<1, 'L'<<1, 'L'<<1, ' '<<1, ' '<<1, ' '<<1, 0x60,
'C'<<1, 'Z'<<1, '0'<<1, 'R'<<1, 'R'<<1, 'R'<<1, 0x61,
0x03, 0xF0};
 
boolean bit;
int fcslo, fcshi; // variabloes for calculating FCS (CRC)
int stuff; // stuff counter for extra 0
int flag_flag; // if it is sending flag (7E)
int fcs_flag; // if it is sending Frame Check Sequence
int i; // for for
 
void flipout() //flips the state of output pin a_1
{
stuff = 0; //since this is a 0, reset the stuff counter
if (bit)
{
bit=FALSE; //if the state of the pin was low, make it high.
}
else
{
bit=TRUE; //if the state of the pin was high make it low
}
}
 
void fcsbit(byte tbyte)
{
#asm
BCF STATUS,0
RRF fcshi,F // rotates the entire 16 bits
RRF fcslo,F // to the right
#endasm
if (((STATUS & 0x01)^(tbyte)) ==0x01)
{
fcshi = fcshi^0x84;
fcslo = fcslo^0x08;
}
}
 
void SendBit ()
{
if (bit)
{
output_high(TXo);
PERIODAH;
output_low(TXo);
PERIODAH;
output_high(TXo);
PERIODAH;
output_low(TXo);
TAILH;
}
else
{
output_high(TXo);
PERIODAL;
output_low(TXo);
TAILL;
};
}
 
void SendByte (byte inbyte)
{
int k, bt;
 
for (k=0;k<8;k++) //do the following for each of the 8 bits in the byte
{
bt = inbyte & 0x01; //strip off the rightmost bit of the byte to be sent (inbyte)
if ((fcs_flag == FALSE) & (flag_flag == FALSE)) fcsbit(bt); //do FCS calc, but only if this
//is not a flag or fcs byte
if (bt == 0)
{
flipout();
} // if this bit is a zero, flip the output state
else
{ //otherwise if it is a 1, do the following:
if (flag_flag == FALSE) stuff++; //increment the count of consequtive 1's
if ((flag_flag == FALSE) & (stuff == 5))
{ //stuff an extra 0, if 5 1's in a row
SendBit();
flipout(); //flip the output state to stuff a 0
}//end of if
}//end of else
// delay_us(850); //introduces a delay that creates 1200 baud
SendBit();
inbyte = inbyte>>1; //go to the next bit in the byte
}//end of for
}//end of SendByte
 
void SendPacket(char *data)
{
bit=FALSE;
 
fcslo=fcshi=0xFF; //The 2 FCS Bytes are initialized to FF
stuff = 0; //The variable stuff counts the number of 1's in a row. When it gets to 5
// it is time to stuff a 0.
 
// output_low(PTT); // Blinking LED
// delay_ms(1000);
// output_high(PTT);
 
flag_flag = TRUE; //The variable flag is true if you are transmitted flags (7E's) false otherwise.
fcs_flag = FALSE; //The variable fcsflag is true if you are transmitting FCS bytes, false otherwise.
 
for(i=0; i<10; i++) SendByte(0x7E); //Sends flag bytes. Adjust length for txdelay
//each flag takes approx 6.7 ms
flag_flag = FALSE; //done sending flags
 
for(i=0; i<16; i++) SendByte(SendData[i]); //send the packet bytes
 
for(i=0; 0 != *data; i++)
{
SendByte(*data); //send the packet bytes
data++;
};
 
fcs_flag = TRUE; //about to send the FCS bytes
fcslo =fcslo^0xff; //must XOR them with FF before sending
fcshi = fcshi^0xff;
SendByte(fcslo); //send the low byte of fcs
SendByte(fcshi); //send the high byte of fcs
fcs_flag = FALSE; //done sending FCS
flag_flag = TRUE; //about to send flags
SendByte(0x7e); // Send a flag to end packet
}
 
#list
/roboti/istrobot/merkur/PIC16F88/turn_R/tank.BAK
0,0 → 1,339
#include "tank.h"
 
#define DEBUG
 
#define TXo PIN_A3 // To the transmitter modulator
#include "AX25.c" // podprogram pro prenos telemetrie
 
unsigned int8 sensors; // pomocna promenna pro cteni cidel na caru
unsigned int8 line; // na ktere strane byla detekovana cara
unsigned int8 speed; // rychlost zataceni
unsigned int8 rovinka; // pocitadlo pro zjisteni rovneho useku
unsigned int8 last; // kde byla cara, kdyz byly minule cidla mimo
unsigned int8 movement; // obsahuje aktualni smer zataceni
unsigned int8 dira; // pocita dobu po kterou je ztracena cara
 
// Konstanty pro dynamiku pohybu
#define T_DIRA 120 // po jakem case zataceni se detekuje dira
#define INC_SPEED 1 // prirustek rychlosti v jednom kroku
#define FW_POMALU 230 // trochu mimo caru vnitrni pas
#define FW_ZATACKA 240 // rychlost vnejsiho kola pri zataceni
#define FW_STREDNE 240 // trochu mimo caru vnejsi pas
#define COUVANI 750 // couvnuti zpet na caru, po detekci diry
#define PRES_DIRU 300
#define MAX_ROVINKA (255-FW_STREDNE)
#define TRESHOLD 6 // rozhodovaci uroven komparatoru, 0xF = 0.75*Vdd
#define BUMPER_TRESHOLD 128
#define CIK_CAK 30000
#define T_CIHLA 50 // perioda detekce cihly
 
//motory //Napred vypnout potom zapnout!
#define FR output_low(PIN_B5); output_high(PIN_B4) // Vpred
#define FL output_low(PIN_B7); output_high(PIN_B6)
#define BR output_low(PIN_B4); output_high(PIN_B5) // Vzad
#define BL output_low(PIN_B6); output_high(PIN_B7)
#define STOPR output_low(PIN_B4);output_low(PIN_B5) // Zastav
#define STOPL output_low(PIN_B6);output_low(PIN_B7)
 
#define L 0b10 // left
#define R 0b01 // right
#define S 0b11 // straight
 
//cidla
#define RSENSOR C2OUT // Senzory na caru
#define LSENSOR C1OUT
#define BUMPER PIN_A4 // Senzor na cihlu
 
#define DIAG_SERVO PIN_B3 // Propojka pro diagnosticky mod
#define DIAG_SENSORS PIN_B2 // Propojka pro diagnosticky mod
 
#DEFINE SOUND_HI PIN_A6 // komplementarni vystupy pro piezo pipak
#DEFINE SOUND_LO PIN_A7
 
char AXstring[40]; // Buffer pro prenos telemetrie
 
// makro pro PWM
#define GO(motor, direction, power) if(get_timer0()<=power) \
{direction##motor;} else {stop##motor;}
 
#int_TIMER2
void TIMER2_isr()
{
if (speed<255) speed+=INC_SPEED;
if (rovinka<MAX_ROVINKA) rovinka++;
if (dira<=T_DIRA) dira++;
}
// Primitivni Pipani
void beep(unsigned int16 period, unsigned int16 length)
{
unsigned int16 nn;
 
for(nn=length; nn>0; nn--)
{
output_high(SOUND_HI);output_low(SOUND_LO);
delay_us(period);
output_high(SOUND_LO);output_low(SOUND_HI);
delay_us(period);
}
}
/******************************************************************************/
void diagnostika()
{
unsigned int16 n;
 
while (input(DIAG_SERVO)) // Propojka, ktera spousti diagnostiku
{
for (n=500; n<800; n+=100)
{
beep(n,n); //beep UP
};
Delay_ms(1000);
//zastav vse
STOPL; STOPR;
//pravy pas
FR; Delay_ms(1000); STOPR; Delay_ms(1000);
BR; Delay_ms(1000); STOPR; Delay_ms(1000);
Beep(880,100); Delay_ms(1000);
//levy pas
FL; Delay_ms(1000); STOPL; Delay_ms(1000);
BL; Delay_ms(1000); STOPL; Delay_ms(1000);
Beep(880,100); Delay_ms(1000);
//oba pasy
FL; FR; Delay_ms(1000); STOPL; STOPR; Delay_ms(1000);
BL; BR; Delay_ms(1000); STOPL; STOPR; Delay_ms(1000);
};
while (input(DIAG_SENSORS)) // spusteni diagnostiky cidel
{
if (RSENSOR) beep(900,500);
if (LSENSOR) beep(800,500);
if ((read_adc(ADC_READ_ONLY)<BUMPER_TRESHOLD)) beep(1000,500);
};
}
///////////////////////////////////////////////////////////////////////////////
void cikcak()
{
unsigned int16 n;
sem1:
n=CIK_CAK;
while (0==RSENSOR||LSENSOR) // zkontroluj caru
{
if (n==CIK_CAK) // zmen smer zataceni
{
n=0;
switch(movement)
{
case L:
FL;BR;
movement=R;
break;
case R:
FR;BL;
movement=L;
break;
case S:
FL;BR;
movement=R;
n=CIK_CAK/2;
break;
}
}
n++;
}
STOPL;STOPR;
line = RSENSOR; // cteni senzoru na caru
line |= LSENSOR << 1;
if (line==0) goto sem1;
// nasli jsme caru
line=S;
}
///////////////////////////////////////////////////////////////////////////////
void objizdka() // objede cihlu
{
unsigned int16 n;
 
BL;BR;Delay_ms(150);
STOPR;STOPL;
beep(900,1000);
// movement=S;
// cikcak();
 
BR; FL; Delay_ms(270); // otoc se 70° do prava
 
FR; FL; Delay_ms(700); // popojed rovne
 
BL; Delay_ms(30); // otoc se 90° do leva
STOPL; FR; Delay_ms(500);
 
FR; FL; Delay_ms(100); // popojed rovne na slepo
for(n=40000;n>0;n--) // popojed rovne ale kontroluj caru
{
line = RSENSOR; // cteni senzoru na caru
line |= LSENSOR << 1;
if (line!=0) {Delay_ms(150); break;}
// Delay_ms(1);
}
 
BR; FL; // otoc se 60° do prava
for(n=40000;n>0;n--)
{
line = RSENSOR; // cteni senzoru na caru
line |= LSENSOR << 1;
if (line!=0) break;
// Delay_ms(1);
}
STOPR; STOPL;
 
movement=L; //R;
cikcak();
dira=0;
}
///////////////////////////////////////////////////////////////////////////////
void prejeddiru() // vyresi diru
{
unsigned int16 n;
unsigned int8 speed_dira;
 
STOPL;STOPR;
speed_dira=speed;
beep(1000,500);
switch (movement) //vrat se zpet na caru
{
case L:
for (n=COUVANI;n>0;n--) {GO(R,B,speed_dira); Delay_ms(1);}
STOPL;STOPR;
break;
case R:
for (n=COUVANI;n>0;n--) {GO(L,B,speed_dira); Delay_ms(1);}
STOPL;STOPR;
break;
case S:
goto sem;
break;
}
beep(1000,500);
 
/*line=0;
FR; BL; Delay_ms(400); // otoc se na caru
beep(1000,500);
while(line==0)
{
line = RSENSOR; // cteni senzoru na caru
line |= LSENSOR << 1;
}
FL;BR; Delay_ms(60); // zabrzdi
STOPL; STOPR;
 
FL; BR; Delay_ms(700); // otacka 180 deg
STOPL; STOPR;*/
 
FR;FL; //popojed rovne
for(n=PRES_DIRU;n>0;n--)
{
line = RSENSOR; // cteni senzoru na caru
line |= LSENSOR << 1;
if (line!=0) break;
Delay_ms(1);
}
sem:
STOPL; STOPR;
movement=S;
cikcak(); // najdi caru
dira=0;
}
///////////////////////////////////////////////////////////////////////////////
void main()
{
unsigned int16 n; // pro FOR
 
STOPL; STOPR; // prepne vystupy na ovladani motoru na output a zastavi
 
setup_oscillator(OSC_4MHZ|OSC_INTRC); // 4 MHz interni RC oscilator
 
port_b_pullups(TRUE); // pullups pro piano na diagnostiku
setup_spi(FALSE);
setup_timer_0(RTCC_INTERNAL|RTCC_DIV_1); // Casovac pro PWM
 
setup_timer_2(T2_DIV_BY_4,255,10); // Casovac pro regulaci
// preruseni kazdych 10ms
setup_adc_ports(sAN2|VSS_VDD); // nastaveni A/D prevodniku pro naraznik
setup_adc(ADC_CLOCK_INTERNAL);
set_adc_channel(2);
setup_timer_1(T1_INTERNAL|T1_DIV_BY_1); // Casovac pro naraznik
setup_ccp1(CCP_COMPARE_RESET_TIMER);
CCP_1=(2^10)-1; // prevod kazdou 1ms
 
setup_comparator(A0_VR_A1_VR); // inicializace komparatoru pro cidla cary
setup_vref(VREF_HIGH|TRESHOLD); // 32 kroku od 0.25 do 0.75 Vdd
 
Beep(1000,200); //double beep
Delay_ms(50);
Beep(1000,200);
Delay_ms(1000); // 1s
 
// povoleni rizeni rychlosti zataceni pres preruseni
enable_interrupts(INT_TIMER2);
enable_interrupts(GLOBAL);
 
/*---------------------------------------------------------------------------*/
sensors=S;
line=S;
last=S;
movement=S;
speed=FW_POMALU;
 
diagnostika();
//cikcak(); // toc se, abys nasel caru
Delay_ms(500);
Beep(1000,200);
Delay_ms(500);
 
while(true) // hlavni smycka (jizda podle cary)
{
sensors = RSENSOR; // cteni senzoru na caru
sensors |= LSENSOR << 1;
 
if ((read_adc(ADC_READ_ONLY)<BUMPER_TRESHOLD) && (dira<=T_CIHLA)) objizdka();
 
switch (sensors) // zatacej podle toho, kde vidis caru
{
case S: // rovne
FL; FR; // pokud se jede dlouho rovne, tak pridej
dira=0;
movement=S;
continue;
case L: // trochu vlevo
GO(L, F, FW_POMALU+rovinka); GO(R, F, FW_STREDNE+rovinka);
line=L;
dira=0;
movement=L;
continue;
case R: // trochu vpravo
GO(R, F, FW_POMALU+rovinka); GO(L, F, FW_STREDNE+rovinka);
line=R;
dira=0;
movement=R;
continue;
default: // kdyz jsou obe cidla mimo caru, tak pokracuj dal
}
rovinka=0;
if (dira>=T_DIRA) prejeddiru();
if (last!=line) // pokud si prejel caru z jedne strany na druhou stranu, tak zabrzdi
{
last=line;
speed=FW_ZATACKA;
}
if (L==line) // kdyz jsou obe cidla mimo caru, zatoc na caru
{
STOPL;
GO(R, F, speed);
movement=L;
}
else
{
STOPR;
GO(L, F, speed);
movement=R;
}
} // while(true)
}
 
/roboti/istrobot/merkur/PIC16F88/turn_R/tank.HEX
0,0 → 1,202
:1000000000308A00722C0000FF00030E8301A10063
:100010007F08A0000A08A8008A01A00E0408A20018
:100020007708A3007808A4007908A5007A08A6003C
:100030007B08A700831383128C308400801C222845
:100040008C183528220884002308F7002408F800BB
:100050002508F9002608FA002708FB0028088A006E
:10006000210E8300FF0E7F0E09008A113728420FF0
:100070003A283C280130C20743080E3C0318C30A43
:100080004608783C0318C60A8C108A1122281230C0
:100090008316A202031C5A28A2308400FC3080057B
:1000A0000310800C800C000803195A2858280000FF
:1000B000800B5728831200347D088316A1007C082A
:1000C000A000A008031D6728A108031986280513AE
:1000D00083120517831685138312851374088316FC
:1000E000A200831247208316851383128517831677
:1000F00005138312051374088316A2008312472088
:10010000831620080319A103A00361288312003479
:1001100074308400000803199C280130F800F701AE
:10012000F70B9028F80B8F284A30F700F70B96282A
:1001300000000000800B8D28003483168615831282
:10014000861DC8290130F200F430F1007208033C2A
:10015000031CBE28031DB02871081F3C031CBE28C9
:100160007208F5007108F4007208FD007108FC00C7
:100170005C206430F1070318F20AA6280430F3006B
:10018000FA30F4008820F30BC0288316061383127C
:1001900006138316861383128613831606128312A0
:1001A0000612831686128312861283168612831213
:1001B000861283160612831206160430F300FA30F4
:1001C000F4008820F30BDF28831606128312061230
:1001D00083168612831286120430F300FA30F4007C
:1001E0008820F30BEE28831606128312061283165C
:1001F0008612831286160430F300FA30F400882049
:10020000F30BFD288316061283120612831686123C
:10021000831286120430F300FA30F4008820F30BC6
:100220000C290330F5007030F400FD016430FC004F
:100230005C200430F300FA30F4008820F30B1B2913
:1002400083168613831286138316061383120617EA
:100250000430F300FA30F4008820F30B2A298316C7
:100260000613831206138316861383128613043033
:10027000F300FA30F4008820F30B392983160613B3
:100280008312061383168613831286170430F30035
:10029000FA30F4008820F30B4829831606138312E2
:1002A000061383168613831286130430F300FA3084
:1002B000F4008820F30B57290330F5007030F40068
:1002C000FD016430FC005C200430F300FA30F400DF
:1002D0008820F30B662983168613831286138316F0
:1002E000061383120617831686128312861283164C
:1002F0000612831206160430F300FA30F400882048
:10030000F30B7D29831606138312061383168613B7
:100310008312861383160612831206128316861220
:10032000831286120430F300FA30F4008820F30BB5
:1003300094298316061383120613831686138312D9
:1003400086178316061283120612831686128312EC
:1003500086160430F300FA30F4008820F30BAB2942
:1003600083160613831206138316861383128613CD
:1003700083160612831206128316861283128612C1
:100380000430F300FA30F4008820F30BC2299D28D2
:10039000831606158312061DFB2983169C1FDB2975
:1003A0000330F5008430F4000130FD00F430FC002F
:1003B00083125C2083161C1FE8290330F5002030CF
:1003C000F4000130FD00F430FC0083125C20831641
:1003D00083121F1DED298316E8291E087F3C031C8C
:1003E000FA290330F500E830F4000130FD00F43064
:1003F000FC005C20C8298A11202D7530F5003030B2
:10040000F400003083169C1B0130003A03190A2ABD
:100410001C1F642A7408303C031D5E2A7508753C55
:10042000031D5E2AF501F40183124508023A0319FF
:10043000202A033A0319332A023A0319462A5D2A6D
:1004400083168613831286138316061383120617E8
:1004500083160612831206128316861283128616DC
:100460000130C5005D2A8316861283128612831618
:1004700006128312061683160613831206138316BA
:100480008613831286170230C5005D2A83168613F1
:100490008312861383160613831206178316061219
:1004A0008312061283168612831286160130C50047
:1004B0003A30F5009830F4005D2A8316F40A0319E7
:1004C000F50A8312012A8316061383120613831674
:1004D000861383128613831606128312061283165E
:1004E000861283128612C10183169C1F7A2A8312F8
:1004F000C10A831600301C1B0130F7000310F70DF2
:1005000077088312C104C1080319FD290330C10013
:100510000034831606138312061383168613831280
:10052000861783160612831206128316861283120A
:1005300086169630F400882083160612831206125F
:1005400083168612831286128316061383120613ED
:1005500083168613831286130330F5008430F4006B
:100560000330FD00E830FC005C2083160612831285
:10057000061283168612831286168316861383123A
:10058000861383160613831206170230F300873092
:10059000F4008820F30BC72A831686128312861272
:1005A0008316061283120616831686138312861389
:1005B00083160613831206170230F300FA30F40094
:1005C0008820F30BDE2A8316061383120613831684
:1005D0008613831286171E30F400882083160613B4
:1005E00083120613831686138312861383168612CC
:1005F0008312861283160612831206160230F30047
:10060000FA30F4008820F30B002B83168612831235
:100610008612831606128312061683168613831219
:10062000861383160613831206176430F40088209D
:100630009C30F2004030F100F108031D222BF2083B
:1006400003193E2BC10183169C1F292B8312C10A5B
:10065000831600301C1B0130F7000310F70D7708DC
:100660008312C104C1080319392B9630F400882085
:100670003E2B71080319F203F1031C2B831606129B
:100680008312061283168612831286168316861329
:100690008312861383160613831206179C30F2000A
:1006A0004030F100F108031D582BF2080319702B9C
:1006B000C10183169C1F5F2B8312C10A8316003071
:1006C0001C1B0130F7000310F70D77088312C104DB
:1006D000C108031D702B71080319F203F103522B9B
:1006E000831606128312061283168612831286124E
:1006F000831606138312061383168613831286133A
:100700000230C500FD21C6018A11502D8316061343
:10071000831206138316861383128613831606121A
:100720008312061283168612831286124208F30081
:100730000330F500E830F4000130FD00F430FC0037
:100740005C204508023A0319AC2B033A0319E42B49
:10075000023A03191C2C1E2C0230F200EE30F1007C
:10076000F108031DB62BF2080319D32B01087302FD
:10077000031CC32B831606128312061283168612DD
:1007800083128616CB2B831606128312061283164B
:100790008612831286120130F40088207108031932
:1007A000F203F103B02B831606138312061383168C
:1007B000861383128613831606128312061283167B
:1007C0008612831286121E2C0230F200EE30F100E7
:1007D000F108031DEE2BF20803190B2C010873021C
:1007E000031CFB2B83160613831206138316861332
:1007F00083128617032C831606138312061383169F
:100800008613831286130130F400882071080319BF
:10081000F203F103E82B83160613831206138316E3
:10082000861383128613831606128312061283160A
:100830008612831286121E2C5C2C1E2C0330F500AF
:10084000E830F4000130FD00F430FC005C20831639
:1008500086128312861283160612831206168316D8
:10086000861383128613831606138312061701302C
:10087000F2002C30F100F108031D412CF20803199D
:100880005C2CC10183169C1F482C8312C10A83165D
:1008900000301C1B0130F7000310F70D770883129E
:1008A000C104C108031D5C2C0130F40088207108CC
:1008B0000319F203F1033B2C83160613831206136C
:1008C000831686138312861383160612831206126A
:1008D00083168612831286120330C500FD21C601DD
:1008E0008A11E62D84011F30830583161F129F1283
:1008F0001B0880399B0007309C001C0883120D13D5
:10090000603083168F0082308312A9009830AA00CD
:10091000AB004030AC00AD00AE006030AF008630C0
:10092000B000B430B1006030B200A430B300B40005
:10093000B5006130B6000330B700F030B800831660
:1009400006138312061383168613831286138316E7
:1009500006128312061283168612831286126230E2
:1009600083168F0081138312941283160611861446
:100970000612003083129400831694000108C739D0
:10098000083881004830F800053883129200FF30A3
:10099000831692001F129F121B08803904389B0097
:1009A0001F1383121F179F1783169F1383121F1481
:1009B0001030F8001F08C73978049F008530900078
:1009C000831686150B308312970096010730950029
:1009D000023083169C000508033885000330F700B9
:1009E000F70BF02C1C0883120D13863083169D0024
:1009F0000330F500E830F400FD01C830FC0083123C
:100A00005C203230F40088200330F500E830F40038
:100A1000FD01C830FC005C200430F100FA30F40025
:100A20008820F10B0E2D83168C14C03083128B049A
:100A30000330C000C100C400C500E630C2009D28DC
:100A40000230F100FA30F4008820F10B222D03303F
:100A5000F500E830F400FD01C830FC005C200230F5
:100A6000F100FA30F4008820F10B312DC00183161B
:100A70009C1F3D2D8312C00A831600301C1B0130C1
:100A8000F7000310F70D77088312C0041F19462DD5
:100A90001E087F3C031C502D4608323C0318892A4F
:100AA0004008033A03195B2D013A03196F2D033AED
:100AB0000319A82DE12D831686138312861383163E
:100AC0000613831206178316861283128612831664
:100AD000061283120616C6010330C500362D010822
:100AE000F100E630430771020319782D0318812DB8
:100AF0008316861383128613831606138312061732
:100B0000892D831606138312061383168613831208
:100B100086130108F100F030430771020319922D8A
:100B200003189B2D831686128312861283160612D3
:100B300083120616A32D831606128312061283163D
:100B40008612831286120230C100C601C500362DFE
:100B50000108F100E630430771020319B12D0318B3
:100B6000BA2D8316861283128612831606128312FA
:100B70000616C22D831606128312061283168612DB
:100B8000831286120108F100F03043077102031945
:100B9000CB2D0318D42D8316861383128613831648
:100BA000061383120617DC2D831606138312061311
:100BB00083168613831286130130C100C601C50057
:100BC000362DC3014608773C031C862B410844029E
:100BD0000319EE2D4108C400F030C2004108023C68
:100BE000031D122E83160613831206138316861313
:100BF0008312861301084202031C072E83168612F5
:100C00008312861283160612831206160F2E83167F
:100C1000061283120612831686128312861202307F
:100C2000C500312E83160612831206128316861211
:100C30008312861201084202031C272E8316861394
:100C40008312861383160613831206172F2E83161C
:100C5000061383120613831686138312861301303C
:060C6000C500362D630003
:04400E00383FFC3FFC
:00000001FF
;PIC16F88
/roboti/istrobot/merkur/PIC16F88/turn_R/tank.LST
0,0 → 1,1932
CCS PCM C Compiler, Version 3.221, 27853 27-IV-05 14:16
 
Filename: D:\KAKLIK\programy\PIC_C\roboti\merkur\PIC16F88\turn_R\tank.LST
 
ROM used: 1587 words (39%)
Largest free fragment is 2048
RAM used: 87 (50%) at main() level
98 (56%) worst case
Stack: 4 worst case (3 in main + 1 for interrupts)
 
*
0000: MOVLW 00
0001: MOVWF 0A
0002: GOTO 472
0003: NOP
0004: MOVWF 7F
0005: SWAPF 03,W
0006: CLRF 03
0007: MOVWF 21
0008: MOVF 7F,W
0009: MOVWF 20
000A: MOVF 0A,W
000B: MOVWF 28
000C: CLRF 0A
000D: SWAPF 20,F
000E: MOVF 04,W
000F: MOVWF 22
0010: MOVF 77,W
0011: MOVWF 23
0012: MOVF 78,W
0013: MOVWF 24
0014: MOVF 79,W
0015: MOVWF 25
0016: MOVF 7A,W
0017: MOVWF 26
0018: MOVF 7B,W
0019: MOVWF 27
001A: BCF 03.7
001B: BCF 03.5
001C: MOVLW 8C
001D: MOVWF 04
001E: BTFSS 00.1
001F: GOTO 022
0020: BTFSC 0C.1
0021: GOTO 035
0022: MOVF 22,W
0023: MOVWF 04
0024: MOVF 23,W
0025: MOVWF 77
0026: MOVF 24,W
0027: MOVWF 78
0028: MOVF 25,W
0029: MOVWF 79
002A: MOVF 26,W
002B: MOVWF 7A
002C: MOVF 27,W
002D: MOVWF 7B
002E: MOVF 28,W
002F: MOVWF 0A
0030: SWAPF 21,W
0031: MOVWF 03
0032: SWAPF 7F,F
0033: SWAPF 7F,W
0034: RETFIE
0035: BCF 0A.3
0036: GOTO 037
.................... #include "tank.h"
.................... #include <16F88.h>
.................... //////// Standard Header file for the PIC16F88 device ////////////////
.................... #device PIC16F88
.................... #list
....................
.................... #device adc=8
.................... #fuses NOWDT,INTRC_IO, NOPUT, MCLR, NOBROWNOUT, NOLVP, NOCPD, NOWRT, NODEBUG, NOPROTECT, NOFCMEN, NOIESO
.................... #use delay(clock=4000000)
*
0047: MOVLW 12
0048: BSF 03.5
0049: SUBWF 22,F
004A: BTFSS 03.0
004B: GOTO 05A
004C: MOVLW A2
004D: MOVWF 04
004E: MOVLW FC
004F: ANDWF 00,F
0050: BCF 03.0
0051: RRF 00,F
0052: RRF 00,F
0053: MOVF 00,W
0054: BTFSC 03.2
0055: GOTO 05A
0056: GOTO 058
0057: NOP
0058: DECFSZ 00,F
0059: GOTO 057
005A: BCF 03.5
005B: RETLW 00
*
0088: MOVLW 74
0089: MOVWF 04
008A: MOVF 00,W
008B: BTFSC 03.2
008C: GOTO 09C
008D: MOVLW 01
008E: MOVWF 78
008F: CLRF 77
0090: DECFSZ 77,F
0091: GOTO 090
0092: DECFSZ 78,F
0093: GOTO 08F
0094: MOVLW 4A
0095: MOVWF 77
0096: DECFSZ 77,F
0097: GOTO 096
0098: NOP
0099: NOP
009A: DECFSZ 00,F
009B: GOTO 08D
009C: RETLW 00
....................
....................
....................
.................... #define DEBUG
....................
.................... #define TXo PIN_A3 // To the transmitter modulator
.................... #include "AX25.c" // podprogram pro prenos telemetrie
.................... #list
....................
....................
.................... unsigned int8 sensors; // pomocna promenna pro cteni cidel na caru
.................... unsigned int8 line; // na ktere strane byla detekovana cara
.................... unsigned int8 speed; // rychlost zataceni
.................... unsigned int8 rovinka; // pocitadlo pro zjisteni rovneho useku
.................... unsigned int8 last; // kde byla cara, kdyz byly minule cidla mimo
.................... unsigned int8 movement; // obsahuje aktualni smer zataceni
.................... unsigned int8 dira; // pocita dobu po kterou je ztracena cara
....................
.................... // Konstanty pro dynamiku pohybu
.................... #define T_DIRA 120 // po jakem case zataceni se detekuje dira
.................... #define INC_SPEED 1 // prirustek rychlosti v jednom kroku
.................... #define FW_POMALU 230 // trochu mimo caru vnitrni pas
.................... #define FW_ZATACKA 240 // rychlost vnejsiho kola pri zataceni
.................... #define FW_STREDNE 240 // trochu mimo caru vnejsi pas
.................... #define COUVANI 750 // couvnuti zpet na caru, po detekci diry
.................... #define PRES_DIRU 300
.................... #define MAX_ROVINKA (255-FW_STREDNE)
.................... #define TRESHOLD 6 // rozhodovaci uroven komparatoru, 0xF = 0.75*Vdd
.................... #define BUMPER_TRESHOLD 128
.................... #define CIK_CAK 30000
.................... #define T_CIHLA 50 // perioda detekce cihly
....................
.................... //motory //Napred vypnout potom zapnout!
.................... #define FR output_low(PIN_B5); output_high(PIN_B4) // Vpred
.................... #define FL output_low(PIN_B7); output_high(PIN_B6)
.................... #define BR output_low(PIN_B4); output_high(PIN_B5) // Vzad
.................... #define BL output_low(PIN_B6); output_high(PIN_B7)
.................... #define STOPR output_low(PIN_B4);output_low(PIN_B5) // Zastav
.................... #define STOPL output_low(PIN_B6);output_low(PIN_B7)
....................
.................... #define L 0b10 // left
.................... #define R 0b01 // right
.................... #define S 0b11 // straight
....................
.................... //cidla
.................... #define RSENSOR C2OUT // Senzory na caru
.................... #define LSENSOR C1OUT
.................... #define BUMPER PIN_A4 // Senzor na cihlu
....................
.................... #define DIAG_SERVO PIN_B3 // Propojka pro diagnosticky mod
.................... #define DIAG_SENSORS PIN_B2 // Propojka pro diagnosticky mod
....................
.................... #DEFINE SOUND_HI PIN_A6 // komplementarni vystupy pro piezo pipak
.................... #DEFINE SOUND_LO PIN_A7
....................
.................... char AXstring[40]; // Buffer pro prenos telemetrie
....................
.................... // makro pro PWM
.................... #define GO(motor, direction, power) if(get_timer0()<=power) \
.................... {direction##motor;} else {stop##motor;}
....................
.................... #int_TIMER2
.................... void TIMER2_isr()
.................... {
.................... if (speed<255) speed+=INC_SPEED;
*
0037: INCFSZ 42,W
0038: GOTO 03A
0039: GOTO 03C
003A: MOVLW 01
003B: ADDWF 42,F
.................... if (rovinka<MAX_ROVINKA) rovinka++;
003C: MOVF 43,W
003D: SUBLW 0E
003E: BTFSC 03.0
003F: INCF 43,F
.................... if (dira<=T_DIRA) dira++;
0040: MOVF 46,W
0041: SUBLW 78
0042: BTFSC 03.0
0043: INCF 46,F
.................... }
.................... // Primitivni Pipani
0044: BCF 0C.1
0045: BCF 0A.3
0046: GOTO 022
.................... void beep(unsigned int16 period, unsigned int16 length)
.................... {
.................... unsigned int16 nn;
....................
.................... for(nn=length; nn>0; nn--)
*
005C: MOVF 7D,W
005D: BSF 03.5
005E: MOVWF 21
005F: MOVF 7C,W
0060: MOVWF 20
0061: MOVF 20,F
0062: BTFSS 03.2
0063: GOTO 067
0064: MOVF 21,F
0065: BTFSC 03.2
0066: GOTO 086
.................... {
.................... output_high(SOUND_HI);output_low(SOUND_LO);
0067: BCF 05.6
0068: BCF 03.5
0069: BSF 05.6
006A: BSF 03.5
006B: BCF 05.7
006C: BCF 03.5
006D: BCF 05.7
.................... delay_us(period);
006E: MOVF 74,W
006F: BSF 03.5
0070: MOVWF 22
0071: BCF 03.5
0072: CALL 047
.................... output_high(SOUND_LO);output_low(SOUND_HI);
0073: BSF 03.5
0074: BCF 05.7
0075: BCF 03.5
0076: BSF 05.7
0077: BSF 03.5
0078: BCF 05.6
0079: BCF 03.5
007A: BCF 05.6
.................... delay_us(period);
007B: MOVF 74,W
007C: BSF 03.5
007D: MOVWF 22
007E: BCF 03.5
007F: CALL 047
.................... }
0080: BSF 03.5
0081: MOVF 20,W
0082: BTFSC 03.2
0083: DECF 21,F
0084: DECF 20,F
0085: GOTO 061
.................... }
0086: BCF 03.5
0087: RETLW 00
.................... /******************************************************************************/
.................... void diagnostika()
.................... {
.................... unsigned int16 n;
....................
.................... while (input(DIAG_SERVO)) // Propojka, ktera spousti diagnostiku
.................... {
*
009D: BSF 03.5
009E: BSF 06.3
009F: BCF 03.5
00A0: BTFSS 06.3
00A1: GOTO 1C8
.................... for (n=500; n<800; n+=100)
00A2: MOVLW 01
00A3: MOVWF 72
00A4: MOVLW F4
00A5: MOVWF 71
00A6: MOVF 72,W
00A7: SUBLW 03
00A8: BTFSS 03.0
00A9: GOTO 0BE
00AA: BTFSS 03.2
00AB: GOTO 0B0
00AC: MOVF 71,W
00AD: SUBLW 1F
00AE: BTFSS 03.0
00AF: GOTO 0BE
.................... {
.................... beep(n,n); //beep UP
00B0: MOVF 72,W
00B1: MOVWF 75
00B2: MOVF 71,W
00B3: MOVWF 74
00B4: MOVF 72,W
00B5: MOVWF 7D
00B6: MOVF 71,W
00B7: MOVWF 7C
00B8: CALL 05C
.................... };
00B9: MOVLW 64
00BA: ADDWF 71,F
00BB: BTFSC 03.0
00BC: INCF 72,F
00BD: GOTO 0A6
.................... Delay_ms(1000);
00BE: MOVLW 04
00BF: MOVWF 73
00C0: MOVLW FA
00C1: MOVWF 74
00C2: CALL 088
00C3: DECFSZ 73,F
00C4: GOTO 0C0
.................... //zastav vse
.................... STOPL; STOPR;
00C5: BSF 03.5
00C6: BCF 06.6
00C7: BCF 03.5
00C8: BCF 06.6
00C9: BSF 03.5
00CA: BCF 06.7
00CB: BCF 03.5
00CC: BCF 06.7
00CD: BSF 03.5
00CE: BCF 06.4
00CF: BCF 03.5
00D0: BCF 06.4
00D1: BSF 03.5
00D2: BCF 06.5
00D3: BCF 03.5
00D4: BCF 06.5
.................... //pravy pas
.................... FR; Delay_ms(1000); STOPR; Delay_ms(1000);
00D5: BSF 03.5
00D6: BCF 06.5
00D7: BCF 03.5
00D8: BCF 06.5
00D9: BSF 03.5
00DA: BCF 06.4
00DB: BCF 03.5
00DC: BSF 06.4
00DD: MOVLW 04
00DE: MOVWF 73
00DF: MOVLW FA
00E0: MOVWF 74
00E1: CALL 088
00E2: DECFSZ 73,F
00E3: GOTO 0DF
00E4: BSF 03.5
00E5: BCF 06.4
00E6: BCF 03.5
00E7: BCF 06.4
00E8: BSF 03.5
00E9: BCF 06.5
00EA: BCF 03.5
00EB: BCF 06.5
00EC: MOVLW 04
00ED: MOVWF 73
00EE: MOVLW FA
00EF: MOVWF 74
00F0: CALL 088
00F1: DECFSZ 73,F
00F2: GOTO 0EE
.................... BR; Delay_ms(1000); STOPR; Delay_ms(1000);
00F3: BSF 03.5
00F4: BCF 06.4
00F5: BCF 03.5
00F6: BCF 06.4
00F7: BSF 03.5
00F8: BCF 06.5
00F9: BCF 03.5
00FA: BSF 06.5
00FB: MOVLW 04
00FC: MOVWF 73
00FD: MOVLW FA
00FE: MOVWF 74
00FF: CALL 088
0100: DECFSZ 73,F
0101: GOTO 0FD
0102: BSF 03.5
0103: BCF 06.4
0104: BCF 03.5
0105: BCF 06.4
0106: BSF 03.5
0107: BCF 06.5
0108: BCF 03.5
0109: BCF 06.5
010A: MOVLW 04
010B: MOVWF 73
010C: MOVLW FA
010D: MOVWF 74
010E: CALL 088
010F: DECFSZ 73,F
0110: GOTO 10C
.................... Beep(880,100); Delay_ms(1000);
0111: MOVLW 03
0112: MOVWF 75
0113: MOVLW 70
0114: MOVWF 74
0115: CLRF 7D
0116: MOVLW 64
0117: MOVWF 7C
0118: CALL 05C
0119: MOVLW 04
011A: MOVWF 73
011B: MOVLW FA
011C: MOVWF 74
011D: CALL 088
011E: DECFSZ 73,F
011F: GOTO 11B
.................... //levy pas
.................... FL; Delay_ms(1000); STOPL; Delay_ms(1000);
0120: BSF 03.5
0121: BCF 06.7
0122: BCF 03.5
0123: BCF 06.7
0124: BSF 03.5
0125: BCF 06.6
0126: BCF 03.5
0127: BSF 06.6
0128: MOVLW 04
0129: MOVWF 73
012A: MOVLW FA
012B: MOVWF 74
012C: CALL 088
012D: DECFSZ 73,F
012E: GOTO 12A
012F: BSF 03.5
0130: BCF 06.6
0131: BCF 03.5
0132: BCF 06.6
0133: BSF 03.5
0134: BCF 06.7
0135: BCF 03.5
0136: BCF 06.7
0137: MOVLW 04
0138: MOVWF 73
0139: MOVLW FA
013A: MOVWF 74
013B: CALL 088
013C: DECFSZ 73,F
013D: GOTO 139
.................... BL; Delay_ms(1000); STOPL; Delay_ms(1000);
013E: BSF 03.5
013F: BCF 06.6
0140: BCF 03.5
0141: BCF 06.6
0142: BSF 03.5
0143: BCF 06.7
0144: BCF 03.5
0145: BSF 06.7
0146: MOVLW 04
0147: MOVWF 73
0148: MOVLW FA
0149: MOVWF 74
014A: CALL 088
014B: DECFSZ 73,F
014C: GOTO 148
014D: BSF 03.5
014E: BCF 06.6
014F: BCF 03.5
0150: BCF 06.6
0151: BSF 03.5
0152: BCF 06.7
0153: BCF 03.5
0154: BCF 06.7
0155: MOVLW 04
0156: MOVWF 73
0157: MOVLW FA
0158: MOVWF 74
0159: CALL 088
015A: DECFSZ 73,F
015B: GOTO 157
.................... Beep(880,100); Delay_ms(1000);
015C: MOVLW 03
015D: MOVWF 75
015E: MOVLW 70
015F: MOVWF 74
0160: CLRF 7D
0161: MOVLW 64
0162: MOVWF 7C
0163: CALL 05C
0164: MOVLW 04
0165: MOVWF 73
0166: MOVLW FA
0167: MOVWF 74
0168: CALL 088
0169: DECFSZ 73,F
016A: GOTO 166
.................... //oba pasy
.................... FL; FR; Delay_ms(1000); STOPL; STOPR; Delay_ms(1000);
016B: BSF 03.5
016C: BCF 06.7
016D: BCF 03.5
016E: BCF 06.7
016F: BSF 03.5
0170: BCF 06.6
0171: BCF 03.5
0172: BSF 06.6
0173: BSF 03.5
0174: BCF 06.5
0175: BCF 03.5
0176: BCF 06.5
0177: BSF 03.5
0178: BCF 06.4
0179: BCF 03.5
017A: BSF 06.4
017B: MOVLW 04
017C: MOVWF 73
017D: MOVLW FA
017E: MOVWF 74
017F: CALL 088
0180: DECFSZ 73,F
0181: GOTO 17D
0182: BSF 03.5
0183: BCF 06.6
0184: BCF 03.5
0185: BCF 06.6
0186: BSF 03.5
0187: BCF 06.7
0188: BCF 03.5
0189: BCF 06.7
018A: BSF 03.5
018B: BCF 06.4
018C: BCF 03.5
018D: BCF 06.4
018E: BSF 03.5
018F: BCF 06.5
0190: BCF 03.5
0191: BCF 06.5
0192: MOVLW 04
0193: MOVWF 73
0194: MOVLW FA
0195: MOVWF 74
0196: CALL 088
0197: DECFSZ 73,F
0198: GOTO 194
.................... BL; BR; Delay_ms(1000); STOPL; STOPR; Delay_ms(1000);
0199: BSF 03.5
019A: BCF 06.6
019B: BCF 03.5
019C: BCF 06.6
019D: BSF 03.5
019E: BCF 06.7
019F: BCF 03.5
01A0: BSF 06.7
01A1: BSF 03.5
01A2: BCF 06.4
01A3: BCF 03.5
01A4: BCF 06.4
01A5: BSF 03.5
01A6: BCF 06.5
01A7: BCF 03.5
01A8: BSF 06.5
01A9: MOVLW 04
01AA: MOVWF 73
01AB: MOVLW FA
01AC: MOVWF 74
01AD: CALL 088
01AE: DECFSZ 73,F
01AF: GOTO 1AB
01B0: BSF 03.5
01B1: BCF 06.6
01B2: BCF 03.5
01B3: BCF 06.6
01B4: BSF 03.5
01B5: BCF 06.7
01B6: BCF 03.5
01B7: BCF 06.7
01B8: BSF 03.5
01B9: BCF 06.4
01BA: BCF 03.5
01BB: BCF 06.4
01BC: BSF 03.5
01BD: BCF 06.5
01BE: BCF 03.5
01BF: BCF 06.5
01C0: MOVLW 04
01C1: MOVWF 73
01C2: MOVLW FA
01C3: MOVWF 74
01C4: CALL 088
01C5: DECFSZ 73,F
01C6: GOTO 1C2
.................... };
01C7: GOTO 09D
.................... while (input(DIAG_SENSORS)) // spusteni diagnostiky cidel
.................... {
01C8: BSF 03.5
01C9: BSF 06.2
01CA: BCF 03.5
01CB: BTFSS 06.2
01CC: GOTO 1FB
.................... if (RSENSOR) beep(900,500);
01CD: BSF 03.5
01CE: BTFSS 1C.7
01CF: GOTO 1DB
01D0: MOVLW 03
01D1: MOVWF 75
01D2: MOVLW 84
01D3: MOVWF 74
01D4: MOVLW 01
01D5: MOVWF 7D
01D6: MOVLW F4
01D7: MOVWF 7C
01D8: BCF 03.5
01D9: CALL 05C
01DA: BSF 03.5
.................... if (LSENSOR) beep(800,500);
01DB: BTFSS 1C.6
01DC: GOTO 1E8
01DD: MOVLW 03
01DE: MOVWF 75
01DF: MOVLW 20
01E0: MOVWF 74
01E1: MOVLW 01
01E2: MOVWF 7D
01E3: MOVLW F4
01E4: MOVWF 7C
01E5: BCF 03.5
01E6: CALL 05C
01E7: BSF 03.5
.................... if ((read_adc(ADC_READ_ONLY)<BUMPER_TRESHOLD)) beep(1000,500);
01E8: BCF 03.5
01E9: BTFSS 1F.2
01EA: GOTO 1ED
01EB: BSF 03.5
01EC: GOTO 1E8
01ED: MOVF 1E,W
01EE: SUBLW 7F
01EF: BTFSS 03.0
01F0: GOTO 1FA
01F1: MOVLW 03
01F2: MOVWF 75
01F3: MOVLW E8
01F4: MOVWF 74
01F5: MOVLW 01
01F6: MOVWF 7D
01F7: MOVLW F4
01F8: MOVWF 7C
01F9: CALL 05C
.................... };
01FA: GOTO 1C8
.................... }
01FB: BCF 0A.3
01FC: GOTO 520 (RETURN)
.................... ///////////////////////////////////////////////////////////////////////////////
.................... void cikcak()
.................... {
.................... unsigned int16 n;
.................... sem1:
.................... n=CIK_CAK;
01FD: MOVLW 75
01FE: MOVWF 75
01FF: MOVLW 30
0200: MOVWF 74
.................... while (0==RSENSOR||LSENSOR) // zkontroluj caru
.................... {
0201: MOVLW 00
0202: BSF 03.5
0203: BTFSC 1C.7
0204: MOVLW 01
0205: XORLW 00
0206: BTFSC 03.2
0207: GOTO 20A
0208: BTFSS 1C.6
0209: GOTO 264
.................... if (n==CIK_CAK) // zmen smer zataceni
020A: MOVF 74,W
020B: SUBLW 30
020C: BTFSS 03.2
020D: GOTO 25E
020E: MOVF 75,W
020F: SUBLW 75
0210: BTFSS 03.2
0211: GOTO 25E
.................... {
.................... n=0;
0212: CLRF 75
0213: CLRF 74
.................... switch(movement)
.................... {
0214: BCF 03.5
0215: MOVF 45,W
0216: XORLW 02
0217: BTFSC 03.2
0218: GOTO 220
0219: XORLW 03
021A: BTFSC 03.2
021B: GOTO 233
021C: XORLW 02
021D: BTFSC 03.2
021E: GOTO 246
021F: GOTO 25D
.................... case L:
.................... FL;BR;
0220: BSF 03.5
0221: BCF 06.7
0222: BCF 03.5
0223: BCF 06.7
0224: BSF 03.5
0225: BCF 06.6
0226: BCF 03.5
0227: BSF 06.6
0228: BSF 03.5
0229: BCF 06.4
022A: BCF 03.5
022B: BCF 06.4
022C: BSF 03.5
022D: BCF 06.5
022E: BCF 03.5
022F: BSF 06.5
.................... movement=R;
0230: MOVLW 01
0231: MOVWF 45
.................... break;
0232: GOTO 25D
.................... case R:
.................... FR;BL;
0233: BSF 03.5
0234: BCF 06.5
0235: BCF 03.5
0236: BCF 06.5
0237: BSF 03.5
0238: BCF 06.4
0239: BCF 03.5
023A: BSF 06.4
023B: BSF 03.5
023C: BCF 06.6
023D: BCF 03.5
023E: BCF 06.6
023F: BSF 03.5
0240: BCF 06.7
0241: BCF 03.5
0242: BSF 06.7
.................... movement=L;
0243: MOVLW 02
0244: MOVWF 45
.................... break;
0245: GOTO 25D
.................... case S:
.................... FL;BR;
0246: BSF 03.5
0247: BCF 06.7
0248: BCF 03.5
0249: BCF 06.7
024A: BSF 03.5
024B: BCF 06.6
024C: BCF 03.5
024D: BSF 06.6
024E: BSF 03.5
024F: BCF 06.4
0250: BCF 03.5
0251: BCF 06.4
0252: BSF 03.5
0253: BCF 06.5
0254: BCF 03.5
0255: BSF 06.5
.................... movement=R;
0256: MOVLW 01
0257: MOVWF 45
.................... n=CIK_CAK/2;
0258: MOVLW 3A
0259: MOVWF 75
025A: MOVLW 98
025B: MOVWF 74
.................... break;
025C: GOTO 25D
025D: BSF 03.5
.................... }
.................... }
.................... n++;
025E: INCF 74,F
025F: BTFSC 03.2
0260: INCF 75,F
.................... }
0261: BCF 03.5
0262: GOTO 201
0263: BSF 03.5
.................... STOPL;STOPR;
0264: BCF 06.6
0265: BCF 03.5
0266: BCF 06.6
0267: BSF 03.5
0268: BCF 06.7
0269: BCF 03.5
026A: BCF 06.7
026B: BSF 03.5
026C: BCF 06.4
026D: BCF 03.5
026E: BCF 06.4
026F: BSF 03.5
0270: BCF 06.5
0271: BCF 03.5
0272: BCF 06.5
.................... line = RSENSOR; // cteni senzoru na caru
0273: CLRF 41
0274: BSF 03.5
0275: BTFSS 1C.7
0276: GOTO 27A
0277: BCF 03.5
0278: INCF 41,F
0279: BSF 03.5
.................... line |= LSENSOR << 1;
027A: MOVLW 00
027B: BTFSC 1C.6
027C: MOVLW 01
027D: MOVWF 77
027E: BCF 03.0
027F: RLF 77,F
0280: MOVF 77,W
0281: BCF 03.5
0282: IORWF 41,F
.................... if (line==0) goto sem1;
0283: MOVF 41,F
0284: BTFSC 03.2
0285: GOTO 1FD
.................... // nasli jsme caru
.................... line=S;
0286: MOVLW 03
0287: MOVWF 41
.................... }
0288: RETLW 00
.................... ///////////////////////////////////////////////////////////////////////////////
.................... void objizdka() // objede cihlu
.................... {
.................... unsigned int16 n;
....................
.................... BL;BR;Delay_ms(150);
0289: BSF 03.5
028A: BCF 06.6
028B: BCF 03.5
028C: BCF 06.6
028D: BSF 03.5
028E: BCF 06.7
028F: BCF 03.5
0290: BSF 06.7
0291: BSF 03.5
0292: BCF 06.4
0293: BCF 03.5
0294: BCF 06.4
0295: BSF 03.5
0296: BCF 06.5
0297: BCF 03.5
0298: BSF 06.5
0299: MOVLW 96
029A: MOVWF 74
029B: CALL 088
.................... STOPR;STOPL;
029C: BSF 03.5
029D: BCF 06.4
029E: BCF 03.5
029F: BCF 06.4
02A0: BSF 03.5
02A1: BCF 06.5
02A2: BCF 03.5
02A3: BCF 06.5
02A4: BSF 03.5
02A5: BCF 06.6
02A6: BCF 03.5
02A7: BCF 06.6
02A8: BSF 03.5
02A9: BCF 06.7
02AA: BCF 03.5
02AB: BCF 06.7
.................... beep(900,1000);
02AC: MOVLW 03
02AD: MOVWF 75
02AE: MOVLW 84
02AF: MOVWF 74
02B0: MOVLW 03
02B1: MOVWF 7D
02B2: MOVLW E8
02B3: MOVWF 7C
02B4: CALL 05C
.................... // movement=S;
.................... // cikcak();
....................
.................... BR; FL; Delay_ms(270); // otoc se 70° do prava
02B5: BSF 03.5
02B6: BCF 06.4
02B7: BCF 03.5
02B8: BCF 06.4
02B9: BSF 03.5
02BA: BCF 06.5
02BB: BCF 03.5
02BC: BSF 06.5
02BD: BSF 03.5
02BE: BCF 06.7
02BF: BCF 03.5
02C0: BCF 06.7
02C1: BSF 03.5
02C2: BCF 06.6
02C3: BCF 03.5
02C4: BSF 06.6
02C5: MOVLW 02
02C6: MOVWF 73
02C7: MOVLW 87
02C8: MOVWF 74
02C9: CALL 088
02CA: DECFSZ 73,F
02CB: GOTO 2C7
....................
.................... FR; FL; Delay_ms(500); // popojed rovne
02CC: BSF 03.5
02CD: BCF 06.5
02CE: BCF 03.5
02CF: BCF 06.5
02D0: BSF 03.5
02D1: BCF 06.4
02D2: BCF 03.5
02D3: BSF 06.4
02D4: BSF 03.5
02D5: BCF 06.7
02D6: BCF 03.5
02D7: BCF 06.7
02D8: BSF 03.5
02D9: BCF 06.6
02DA: BCF 03.5
02DB: BSF 06.6
02DC: MOVLW 02
02DD: MOVWF 73
02DE: MOVLW FA
02DF: MOVWF 74
02E0: CALL 088
02E1: DECFSZ 73,F
02E2: GOTO 2DE
....................
.................... BL; Delay_ms(30); // otoc se 90° do leva
02E3: BSF 03.5
02E4: BCF 06.6
02E5: BCF 03.5
02E6: BCF 06.6
02E7: BSF 03.5
02E8: BCF 06.7
02E9: BCF 03.5
02EA: BSF 06.7
02EB: MOVLW 1E
02EC: MOVWF 74
02ED: CALL 088
.................... STOPL; FR; Delay_ms(500);
02EE: BSF 03.5
02EF: BCF 06.6
02F0: BCF 03.5
02F1: BCF 06.6
02F2: BSF 03.5
02F3: BCF 06.7
02F4: BCF 03.5
02F5: BCF 06.7
02F6: BSF 03.5
02F7: BCF 06.5
02F8: BCF 03.5
02F9: BCF 06.5
02FA: BSF 03.5
02FB: BCF 06.4
02FC: BCF 03.5
02FD: BSF 06.4
02FE: MOVLW 02
02FF: MOVWF 73
0300: MOVLW FA
0301: MOVWF 74
0302: CALL 088
0303: DECFSZ 73,F
0304: GOTO 300
....................
.................... FR; FL; Delay_ms(100); // popojed rovne na slepo
0305: BSF 03.5
0306: BCF 06.5
0307: BCF 03.5
0308: BCF 06.5
0309: BSF 03.5
030A: BCF 06.4
030B: BCF 03.5
030C: BSF 06.4
030D: BSF 03.5
030E: BCF 06.7
030F: BCF 03.5
0310: BCF 06.7
0311: BSF 03.5
0312: BCF 06.6
0313: BCF 03.5
0314: BSF 06.6
0315: MOVLW 64
0316: MOVWF 74
0317: CALL 088
.................... for(n=40000;n>0;n--) // popojed rovne ale kontroluj caru
0318: MOVLW 9C
0319: MOVWF 72
031A: MOVLW 40
031B: MOVWF 71
031C: MOVF 71,F
031D: BTFSS 03.2
031E: GOTO 322
031F: MOVF 72,F
0320: BTFSC 03.2
0321: GOTO 33E
.................... {
.................... line = RSENSOR; // cteni senzoru na caru
0322: CLRF 41
0323: BSF 03.5
0324: BTFSS 1C.7
0325: GOTO 329
0326: BCF 03.5
0327: INCF 41,F
0328: BSF 03.5
.................... line |= LSENSOR << 1;
0329: MOVLW 00
032A: BTFSC 1C.6
032B: MOVLW 01
032C: MOVWF 77
032D: BCF 03.0
032E: RLF 77,F
032F: MOVF 77,W
0330: BCF 03.5
0331: IORWF 41,F
.................... if (line!=0) {Delay_ms(150); break;}
0332: MOVF 41,F
0333: BTFSC 03.2
0334: GOTO 339
0335: MOVLW 96
0336: MOVWF 74
0337: CALL 088
0338: GOTO 33E
.................... // Delay_ms(1);
.................... }
0339: MOVF 71,W
033A: BTFSC 03.2
033B: DECF 72,F
033C: DECF 71,F
033D: GOTO 31C
....................
.................... BR; FL; // otoc se 60° do prava
033E: BSF 03.5
033F: BCF 06.4
0340: BCF 03.5
0341: BCF 06.4
0342: BSF 03.5
0343: BCF 06.5
0344: BCF 03.5
0345: BSF 06.5
0346: BSF 03.5
0347: BCF 06.7
0348: BCF 03.5
0349: BCF 06.7
034A: BSF 03.5
034B: BCF 06.6
034C: BCF 03.5
034D: BSF 06.6
.................... for(n=40000;n>0;n--)
034E: MOVLW 9C
034F: MOVWF 72
0350: MOVLW 40
0351: MOVWF 71
0352: MOVF 71,F
0353: BTFSS 03.2
0354: GOTO 358
0355: MOVF 72,F
0356: BTFSC 03.2
0357: GOTO 370
.................... {
.................... line = RSENSOR; // cteni senzoru na caru
0358: CLRF 41
0359: BSF 03.5
035A: BTFSS 1C.7
035B: GOTO 35F
035C: BCF 03.5
035D: INCF 41,F
035E: BSF 03.5
.................... line |= LSENSOR << 1;
035F: MOVLW 00
0360: BTFSC 1C.6
0361: MOVLW 01
0362: MOVWF 77
0363: BCF 03.0
0364: RLF 77,F
0365: MOVF 77,W
0366: BCF 03.5
0367: IORWF 41,F
.................... if (line!=0) break;
0368: MOVF 41,F
0369: BTFSS 03.2
036A: GOTO 370
.................... // Delay_ms(1);
.................... }
036B: MOVF 71,W
036C: BTFSC 03.2
036D: DECF 72,F
036E: DECF 71,F
036F: GOTO 352
.................... STOPR; STOPL;
0370: BSF 03.5
0371: BCF 06.4
0372: BCF 03.5
0373: BCF 06.4
0374: BSF 03.5
0375: BCF 06.5
0376: BCF 03.5
0377: BCF 06.5
0378: BSF 03.5
0379: BCF 06.6
037A: BCF 03.5
037B: BCF 06.6
037C: BSF 03.5
037D: BCF 06.7
037E: BCF 03.5
037F: BCF 06.7
....................
.................... movement=L; //R;
0380: MOVLW 02
0381: MOVWF 45
.................... cikcak();
0382: CALL 1FD
.................... dira=0;
0383: CLRF 46
.................... }
0384: BCF 0A.3
0385: GOTO 550 (RETURN)
.................... ///////////////////////////////////////////////////////////////////////////////
.................... void prejeddiru() // vyresi diru
.................... {
.................... unsigned int16 n;
.................... unsigned int8 speed_dira;
....................
.................... STOPL;STOPR;
0386: BSF 03.5
0387: BCF 06.6
0388: BCF 03.5
0389: BCF 06.6
038A: BSF 03.5
038B: BCF 06.7
038C: BCF 03.5
038D: BCF 06.7
038E: BSF 03.5
038F: BCF 06.4
0390: BCF 03.5
0391: BCF 06.4
0392: BSF 03.5
0393: BCF 06.5
0394: BCF 03.5
0395: BCF 06.5
.................... speed_dira=speed;
0396: MOVF 42,W
0397: MOVWF 73
.................... beep(1000,500);
0398: MOVLW 03
0399: MOVWF 75
039A: MOVLW E8
039B: MOVWF 74
039C: MOVLW 01
039D: MOVWF 7D
039E: MOVLW F4
039F: MOVWF 7C
03A0: CALL 05C
.................... switch (movement) //vrat se zpet na caru
.................... {
03A1: MOVF 45,W
03A2: XORLW 02
03A3: BTFSC 03.2
03A4: GOTO 3AC
03A5: XORLW 03
03A6: BTFSC 03.2
03A7: GOTO 3E4
03A8: XORLW 02
03A9: BTFSC 03.2
03AA: GOTO 41C
03AB: GOTO 41E
.................... case L:
.................... for (n=COUVANI;n>0;n--) {GO(R,B,speed_dira); Delay_ms(1);}
03AC: MOVLW 02
03AD: MOVWF 72
03AE: MOVLW EE
03AF: MOVWF 71
03B0: MOVF 71,F
03B1: BTFSS 03.2
03B2: GOTO 3B6
03B3: MOVF 72,F
03B4: BTFSC 03.2
03B5: GOTO 3D3
03B6: MOVF 01,W
03B7: SUBWF 73,W
03B8: BTFSS 03.0
03B9: GOTO 3C3
03BA: BSF 03.5
03BB: BCF 06.4
03BC: BCF 03.5
03BD: BCF 06.4
03BE: BSF 03.5
03BF: BCF 06.5
03C0: BCF 03.5
03C1: BSF 06.5
03C2: GOTO 3CB
03C3: BSF 03.5
03C4: BCF 06.4
03C5: BCF 03.5
03C6: BCF 06.4
03C7: BSF 03.5
03C8: BCF 06.5
03C9: BCF 03.5
03CA: BCF 06.5
03CB: MOVLW 01
03CC: MOVWF 74
03CD: CALL 088
03CE: MOVF 71,W
03CF: BTFSC 03.2
03D0: DECF 72,F
03D1: DECF 71,F
03D2: GOTO 3B0
.................... STOPL;STOPR;
03D3: BSF 03.5
03D4: BCF 06.6
03D5: BCF 03.5
03D6: BCF 06.6
03D7: BSF 03.5
03D8: BCF 06.7
03D9: BCF 03.5
03DA: BCF 06.7
03DB: BSF 03.5
03DC: BCF 06.4
03DD: BCF 03.5
03DE: BCF 06.4
03DF: BSF 03.5
03E0: BCF 06.5
03E1: BCF 03.5
03E2: BCF 06.5
.................... break;
03E3: GOTO 41E
.................... case R:
.................... for (n=COUVANI;n>0;n--) {GO(L,B,speed_dira); Delay_ms(1);}
03E4: MOVLW 02
03E5: MOVWF 72
03E6: MOVLW EE
03E7: MOVWF 71
03E8: MOVF 71,F
03E9: BTFSS 03.2
03EA: GOTO 3EE
03EB: MOVF 72,F
03EC: BTFSC 03.2
03ED: GOTO 40B
03EE: MOVF 01,W
03EF: SUBWF 73,W
03F0: BTFSS 03.0
03F1: GOTO 3FB
03F2: BSF 03.5
03F3: BCF 06.6
03F4: BCF 03.5
03F5: BCF 06.6
03F6: BSF 03.5
03F7: BCF 06.7
03F8: BCF 03.5
03F9: BSF 06.7
03FA: GOTO 403
03FB: BSF 03.5
03FC: BCF 06.6
03FD: BCF 03.5
03FE: BCF 06.6
03FF: BSF 03.5
0400: BCF 06.7
0401: BCF 03.5
0402: BCF 06.7
0403: MOVLW 01
0404: MOVWF 74
0405: CALL 088
0406: MOVF 71,W
0407: BTFSC 03.2
0408: DECF 72,F
0409: DECF 71,F
040A: GOTO 3E8
.................... STOPL;STOPR;
040B: BSF 03.5
040C: BCF 06.6
040D: BCF 03.5
040E: BCF 06.6
040F: BSF 03.5
0410: BCF 06.7
0411: BCF 03.5
0412: BCF 06.7
0413: BSF 03.5
0414: BCF 06.4
0415: BCF 03.5
0416: BCF 06.4
0417: BSF 03.5
0418: BCF 06.5
0419: BCF 03.5
041A: BCF 06.5
.................... break;
041B: GOTO 41E
.................... case S:
.................... goto sem;
041C: GOTO 45C
.................... break;
041D: GOTO 41E
.................... }
.................... beep(1000,500);
041E: MOVLW 03
041F: MOVWF 75
0420: MOVLW E8
0421: MOVWF 74
0422: MOVLW 01
0423: MOVWF 7D
0424: MOVLW F4
0425: MOVWF 7C
0426: CALL 05C
....................
.................... /*line=0;
.................... FR; BL; Delay_ms(400); // otoc se na caru
.................... beep(1000,500);
.................... while(line==0)
.................... {
.................... line = RSENSOR; // cteni senzoru na caru
.................... line |= LSENSOR << 1;
.................... }
.................... FL;BR; Delay_ms(60); // zabrzdi
.................... STOPL; STOPR;
....................
.................... FL; BR; Delay_ms(700); // otacka 180 deg
.................... STOPL; STOPR;*/
....................
.................... FR;FL; //popojed rovne
0427: BSF 03.5
0428: BCF 06.5
0429: BCF 03.5
042A: BCF 06.5
042B: BSF 03.5
042C: BCF 06.4
042D: BCF 03.5
042E: BSF 06.4
042F: BSF 03.5
0430: BCF 06.7
0431: BCF 03.5
0432: BCF 06.7
0433: BSF 03.5
0434: BCF 06.6
0435: BCF 03.5
0436: BSF 06.6
.................... for(n=PRES_DIRU;n>0;n--)
0437: MOVLW 01
0438: MOVWF 72
0439: MOVLW 2C
043A: MOVWF 71
043B: MOVF 71,F
043C: BTFSS 03.2
043D: GOTO 441
043E: MOVF 72,F
043F: BTFSC 03.2
0440: GOTO 45C
.................... {
.................... line = RSENSOR; // cteni senzoru na caru
0441: CLRF 41
0442: BSF 03.5
0443: BTFSS 1C.7
0444: GOTO 448
0445: BCF 03.5
0446: INCF 41,F
0447: BSF 03.5
.................... line |= LSENSOR << 1;
0448: MOVLW 00
0449: BTFSC 1C.6
044A: MOVLW 01
044B: MOVWF 77
044C: BCF 03.0
044D: RLF 77,F
044E: MOVF 77,W
044F: BCF 03.5
0450: IORWF 41,F
.................... if (line!=0) break;
0451: MOVF 41,F
0452: BTFSS 03.2
0453: GOTO 45C
.................... Delay_ms(1);
0454: MOVLW 01
0455: MOVWF 74
0456: CALL 088
.................... }
0457: MOVF 71,W
0458: BTFSC 03.2
0459: DECF 72,F
045A: DECF 71,F
045B: GOTO 43B
.................... sem:
.................... STOPL; STOPR;
045C: BSF 03.5
045D: BCF 06.6
045E: BCF 03.5
045F: BCF 06.6
0460: BSF 03.5
0461: BCF 06.7
0462: BCF 03.5
0463: BCF 06.7
0464: BSF 03.5
0465: BCF 06.4
0466: BCF 03.5
0467: BCF 06.4
0468: BSF 03.5
0469: BCF 06.5
046A: BCF 03.5
046B: BCF 06.5
.................... movement=S;
046C: MOVLW 03
046D: MOVWF 45
.................... cikcak(); // najdi caru
046E: CALL 1FD
.................... dira=0;
046F: CLRF 46
.................... }
0470: BCF 0A.3
0471: GOTO 5E6 (RETURN)
.................... ///////////////////////////////////////////////////////////////////////////////
.................... void main()
.................... {
0472: CLRF 04
0473: MOVLW 1F
0474: ANDWF 03,F
0475: BSF 03.5
0476: BCF 1F.4
0477: BCF 1F.5
0478: MOVF 1B,W
0479: ANDLW 80
047A: MOVWF 1B
047B: MOVLW 07
047C: MOVWF 1C
047D: MOVF 1C,W
047E: BCF 03.5
047F: BCF 0D.6
0480: MOVLW 60
0481: BSF 03.5
0482: MOVWF 0F
.................... unsigned int16 n; // pro FOR
....................
.................... STOPL; STOPR; // prepne vystupy na ovladani motoru na output a zastavi
*
049F: BSF 03.5
04A0: BCF 06.6
04A1: BCF 03.5
04A2: BCF 06.6
04A3: BSF 03.5
04A4: BCF 06.7
04A5: BCF 03.5
04A6: BCF 06.7
04A7: BSF 03.5
04A8: BCF 06.4
04A9: BCF 03.5
04AA: BCF 06.4
04AB: BSF 03.5
04AC: BCF 06.5
04AD: BCF 03.5
04AE: BCF 06.5
....................
.................... setup_oscillator(OSC_4MHZ|OSC_INTRC); // 4 MHz interni RC oscilator
04AF: MOVLW 62
04B0: BSF 03.5
04B1: MOVWF 0F
....................
.................... port_b_pullups(TRUE); // pullups pro piano na diagnostiku
04B2: BCF 01.7
.................... setup_spi(FALSE);
04B3: BCF 03.5
04B4: BCF 14.5
04B5: BSF 03.5
04B6: BCF 06.2
04B7: BSF 06.1
04B8: BCF 06.4
04B9: MOVLW 00
04BA: BCF 03.5
04BB: MOVWF 14
04BC: BSF 03.5
04BD: MOVWF 14
.................... setup_timer_0(RTCC_INTERNAL|RTCC_DIV_1); // Casovac pro PWM
04BE: MOVF 01,W
04BF: ANDLW C7
04C0: IORLW 08
04C1: MOVWF 01
....................
.................... setup_timer_2(T2_DIV_BY_4,255,10); // Casovac pro regulaci
04C2: MOVLW 48
04C3: MOVWF 78
04C4: IORLW 05
04C5: BCF 03.5
04C6: MOVWF 12
04C7: MOVLW FF
04C8: BSF 03.5
04C9: MOVWF 12
.................... // preruseni kazdych 10ms
.................... setup_adc_ports(sAN2|VSS_VDD); // nastaveni A/D prevodniku pro naraznik
04CA: BCF 1F.4
04CB: BCF 1F.5
04CC: MOVF 1B,W
04CD: ANDLW 80
04CE: IORLW 04
04CF: MOVWF 1B
.................... setup_adc(ADC_CLOCK_INTERNAL);
04D0: BCF 1F.6
04D1: BCF 03.5
04D2: BSF 1F.6
04D3: BSF 1F.7
04D4: BSF 03.5
04D5: BCF 1F.7
04D6: BCF 03.5
04D7: BSF 1F.0
.................... set_adc_channel(2);
04D8: MOVLW 10
04D9: MOVWF 78
04DA: MOVF 1F,W
04DB: ANDLW C7
04DC: IORWF 78,W
04DD: MOVWF 1F
.................... setup_timer_1(T1_INTERNAL|T1_DIV_BY_1); // Casovac pro naraznik
04DE: MOVLW 85
04DF: MOVWF 10
.................... setup_ccp1(CCP_COMPARE_RESET_TIMER);
04E0: BSF 03.5
04E1: BSF 06.3
04E2: MOVLW 0B
04E3: BCF 03.5
04E4: MOVWF 17
.................... CCP_1=(2^10)-1; // prevod kazdou 1ms
04E5: CLRF 16
04E6: MOVLW 07
04E7: MOVWF 15
....................
.................... setup_comparator(A0_VR_A1_VR); // inicializace komparatoru pro cidla cary
04E8: MOVLW 02
04E9: BSF 03.5
04EA: MOVWF 1C
04EB: MOVF 05,W
04EC: IORLW 03
04ED: MOVWF 05
04EE: MOVLW 03
04EF: MOVWF 77
04F0: DECFSZ 77,F
04F1: GOTO 4F0
04F2: MOVF 1C,W
04F3: BCF 03.5
04F4: BCF 0D.6
.................... setup_vref(VREF_HIGH|TRESHOLD); // 32 kroku od 0.25 do 0.75 Vdd
04F5: MOVLW 86
04F6: BSF 03.5
04F7: MOVWF 1D
....................
.................... Beep(1000,200); //double beep
04F8: MOVLW 03
04F9: MOVWF 75
04FA: MOVLW E8
04FB: MOVWF 74
04FC: CLRF 7D
04FD: MOVLW C8
04FE: MOVWF 7C
04FF: BCF 03.5
0500: CALL 05C
.................... Delay_ms(50);
0501: MOVLW 32
0502: MOVWF 74
0503: CALL 088
.................... Beep(1000,200);
0504: MOVLW 03
0505: MOVWF 75
0506: MOVLW E8
0507: MOVWF 74
0508: CLRF 7D
0509: MOVLW C8
050A: MOVWF 7C
050B: CALL 05C
.................... Delay_ms(1000); // 1s
050C: MOVLW 04
050D: MOVWF 71
050E: MOVLW FA
050F: MOVWF 74
0510: CALL 088
0511: DECFSZ 71,F
0512: GOTO 50E
....................
.................... // povoleni rizeni rychlosti zataceni pres preruseni
.................... enable_interrupts(INT_TIMER2);
0513: BSF 03.5
0514: BSF 0C.1
.................... enable_interrupts(GLOBAL);
0515: MOVLW C0
0516: BCF 03.5
0517: IORWF 0B,F
....................
.................... /*---------------------------------------------------------------------------*/
.................... sensors=S;
0518: MOVLW 03
0519: MOVWF 40
.................... line=S;
051A: MOVWF 41
.................... last=S;
051B: MOVWF 44
.................... movement=S;
051C: MOVWF 45
.................... speed=FW_POMALU;
051D: MOVLW E6
051E: MOVWF 42
....................
.................... diagnostika();
051F: GOTO 09D
.................... //cikcak(); // toc se, abys nasel caru
.................... Delay_ms(500);
0520: MOVLW 02
0521: MOVWF 71
0522: MOVLW FA
0523: MOVWF 74
0524: CALL 088
0525: DECFSZ 71,F
0526: GOTO 522
.................... Beep(1000,200);
0527: MOVLW 03
0528: MOVWF 75
0529: MOVLW E8
052A: MOVWF 74
052B: CLRF 7D
052C: MOVLW C8
052D: MOVWF 7C
052E: CALL 05C
.................... Delay_ms(500);
052F: MOVLW 02
0530: MOVWF 71
0531: MOVLW FA
0532: MOVWF 74
0533: CALL 088
0534: DECFSZ 71,F
0535: GOTO 531
....................
.................... while(true) // hlavni smycka (jizda podle cary)
.................... {
.................... sensors = RSENSOR; // cteni senzoru na caru
0536: CLRF 40
0537: BSF 03.5
0538: BTFSS 1C.7
0539: GOTO 53D
053A: BCF 03.5
053B: INCF 40,F
053C: BSF 03.5
.................... sensors |= LSENSOR << 1;
053D: MOVLW 00
053E: BTFSC 1C.6
053F: MOVLW 01
0540: MOVWF 77
0541: BCF 03.0
0542: RLF 77,F
0543: MOVF 77,W
0544: BCF 03.5
0545: IORWF 40,F
....................
.................... if ((read_adc(ADC_READ_ONLY)<BUMPER_TRESHOLD) && (dira<=T_CIHLA)) objizdka();
0546: BTFSC 1F.2
0547: GOTO 546
0548: MOVF 1E,W
0549: SUBLW 7F
054A: BTFSS 03.0
054B: GOTO 550
054C: MOVF 46,W
054D: SUBLW 32
054E: BTFSC 03.0
054F: GOTO 289
....................
.................... switch (sensors) // zatacej podle toho, kde vidis caru
.................... {
0550: MOVF 40,W
0551: XORLW 03
0552: BTFSC 03.2
0553: GOTO 55B
0554: XORLW 01
0555: BTFSC 03.2
0556: GOTO 56F
0557: XORLW 03
0558: BTFSC 03.2
0559: GOTO 5A8
055A: GOTO 5E1
.................... case S: // rovne
.................... FL; FR; // pokud se jede dlouho rovne, tak pridej
055B: BSF 03.5
055C: BCF 06.7
055D: BCF 03.5
055E: BCF 06.7
055F: BSF 03.5
0560: BCF 06.6
0561: BCF 03.5
0562: BSF 06.6
0563: BSF 03.5
0564: BCF 06.5
0565: BCF 03.5
0566: BCF 06.5
0567: BSF 03.5
0568: BCF 06.4
0569: BCF 03.5
056A: BSF 06.4
.................... dira=0;
056B: CLRF 46
.................... movement=S;
056C: MOVLW 03
056D: MOVWF 45
.................... continue;
056E: GOTO 536
.................... case L: // trochu vlevo
.................... GO(L, F, FW_POMALU+rovinka); GO(R, F, FW_STREDNE+rovinka);
056F: MOVF 01,W
0570: MOVWF 71
0571: MOVLW E6
0572: ADDWF 43,W
0573: SUBWF 71,W
0574: BTFSC 03.2
0575: GOTO 578
0576: BTFSC 03.0
0577: GOTO 581
0578: BSF 03.5
0579: BCF 06.7
057A: BCF 03.5
057B: BCF 06.7
057C: BSF 03.5
057D: BCF 06.6
057E: BCF 03.5
057F: BSF 06.6
0580: GOTO 589
0581: BSF 03.5
0582: BCF 06.6
0583: BCF 03.5
0584: BCF 06.6
0585: BSF 03.5
0586: BCF 06.7
0587: BCF 03.5
0588: BCF 06.7
0589: MOVF 01,W
058A: MOVWF 71
058B: MOVLW F0
058C: ADDWF 43,W
058D: SUBWF 71,W
058E: BTFSC 03.2
058F: GOTO 592
0590: BTFSC 03.0
0591: GOTO 59B
0592: BSF 03.5
0593: BCF 06.5
0594: BCF 03.5
0595: BCF 06.5
0596: BSF 03.5
0597: BCF 06.4
0598: BCF 03.5
0599: BSF 06.4
059A: GOTO 5A3
059B: BSF 03.5
059C: BCF 06.4
059D: BCF 03.5
059E: BCF 06.4
059F: BSF 03.5
05A0: BCF 06.5
05A1: BCF 03.5
05A2: BCF 06.5
.................... line=L;
05A3: MOVLW 02
05A4: MOVWF 41
.................... dira=0;
05A5: CLRF 46
.................... movement=L;
05A6: MOVWF 45
.................... continue;
05A7: GOTO 536
.................... case R: // trochu vpravo
.................... GO(R, F, FW_POMALU+rovinka); GO(L, F, FW_STREDNE+rovinka);
05A8: MOVF 01,W
05A9: MOVWF 71
05AA: MOVLW E6
05AB: ADDWF 43,W
05AC: SUBWF 71,W
05AD: BTFSC 03.2
05AE: GOTO 5B1
05AF: BTFSC 03.0
05B0: GOTO 5BA
05B1: BSF 03.5
05B2: BCF 06.5
05B3: BCF 03.5
05B4: BCF 06.5
05B5: BSF 03.5
05B6: BCF 06.4
05B7: BCF 03.5
05B8: BSF 06.4
05B9: GOTO 5C2
05BA: BSF 03.5
05BB: BCF 06.4
05BC: BCF 03.5
05BD: BCF 06.4
05BE: BSF 03.5
05BF: BCF 06.5
05C0: BCF 03.5
05C1: BCF 06.5
05C2: MOVF 01,W
05C3: MOVWF 71
05C4: MOVLW F0
05C5: ADDWF 43,W
05C6: SUBWF 71,W
05C7: BTFSC 03.2
05C8: GOTO 5CB
05C9: BTFSC 03.0
05CA: GOTO 5D4
05CB: BSF 03.5
05CC: BCF 06.7
05CD: BCF 03.5
05CE: BCF 06.7
05CF: BSF 03.5
05D0: BCF 06.6
05D1: BCF 03.5
05D2: BSF 06.6
05D3: GOTO 5DC
05D4: BSF 03.5
05D5: BCF 06.6
05D6: BCF 03.5
05D7: BCF 06.6
05D8: BSF 03.5
05D9: BCF 06.7
05DA: BCF 03.5
05DB: BCF 06.7
.................... line=R;
05DC: MOVLW 01
05DD: MOVWF 41
.................... dira=0;
05DE: CLRF 46
.................... movement=R;
05DF: MOVWF 45
.................... continue;
05E0: GOTO 536
.................... default: // kdyz jsou obe cidla mimo caru, tak pokracuj dal
.................... }
.................... rovinka=0;
05E1: CLRF 43
.................... if (dira>=T_DIRA) prejeddiru();
05E2: MOVF 46,W
05E3: SUBLW 77
05E4: BTFSS 03.0
05E5: GOTO 386
.................... if (last!=line) // pokud si prejel caru z jedne strany na druhou stranu, tak zabrzdi
05E6: MOVF 41,W
05E7: SUBWF 44,W
05E8: BTFSC 03.2
05E9: GOTO 5EE
.................... {
.................... last=line;
05EA: MOVF 41,W
05EB: MOVWF 44
.................... speed=FW_ZATACKA;
05EC: MOVLW F0
05ED: MOVWF 42
.................... }
.................... if (L==line) // kdyz jsou obe cidla mimo caru, zatoc na caru
05EE: MOVF 41,W
05EF: SUBLW 02
05F0: BTFSS 03.2
05F1: GOTO 612
.................... {
.................... STOPL;
05F2: BSF 03.5
05F3: BCF 06.6
05F4: BCF 03.5
05F5: BCF 06.6
05F6: BSF 03.5
05F7: BCF 06.7
05F8: BCF 03.5
05F9: BCF 06.7
.................... GO(R, F, speed);
05FA: MOVF 01,W
05FB: SUBWF 42,W
05FC: BTFSS 03.0
05FD: GOTO 607
05FE: BSF 03.5
05FF: BCF 06.5
0600: BCF 03.5
0601: BCF 06.5
0602: BSF 03.5
0603: BCF 06.4
0604: BCF 03.5
0605: BSF 06.4
0606: GOTO 60F
0607: BSF 03.5
0608: BCF 06.4
0609: BCF 03.5
060A: BCF 06.4
060B: BSF 03.5
060C: BCF 06.5
060D: BCF 03.5
060E: BCF 06.5
.................... movement=L;
060F: MOVLW 02
0610: MOVWF 45
.................... }
.................... else
0611: GOTO 631
.................... {
.................... STOPR;
0612: BSF 03.5
0613: BCF 06.4
0614: BCF 03.5
0615: BCF 06.4
0616: BSF 03.5
0617: BCF 06.5
0618: BCF 03.5
0619: BCF 06.5
.................... GO(L, F, speed);
061A: MOVF 01,W
061B: SUBWF 42,W
061C: BTFSS 03.0
061D: GOTO 627
061E: BSF 03.5
061F: BCF 06.7
0620: BCF 03.5
0621: BCF 06.7
0622: BSF 03.5
0623: BCF 06.6
0624: BCF 03.5
0625: BSF 06.6
0626: GOTO 62F
0627: BSF 03.5
0628: BCF 06.6
0629: BCF 03.5
062A: BCF 06.6
062B: BSF 03.5
062C: BCF 06.7
062D: BCF 03.5
062E: BCF 06.7
.................... movement=R;
062F: MOVLW 01
0630: MOVWF 45
.................... }
.................... } // while(true)
0631: GOTO 536
.................... }
....................
....................
0632: SLEEP
 
Configuration Fuses:
Word 1: 3F38 NOWDT NOPUT MCLR NOBROWNOUT NOLVP NOCPD NOWRT NODEBUG CCPB0 NOPROTECT INTRC_IO
Word 2: 3FFC NOFCMEN NOIESO
/roboti/istrobot/merkur/PIC16F88/turn_R/tank.PJT
0,0 → 1,40
[PROJECT]
Target=tank.HEX
Development_Mode=
Processor=0x688F
ToolSuite=CCS
 
[Directories]
Include=C:\Program Files\PICC\devices\;C:\Program Files\PICC\drivers\;C:\library\CCS;
Library=
LinkerScript=
 
[Target Data]
FileList=tank.c;
BuildTool=C-COMPILER
OptionString=+FM
AdditionalOptionString=
BuildRequired=1
 
[tank.c]
Type=4
Path=
FileList=
BuildTool=
OptionString=
AdditionalOptionString=
 
[mru-list]
1=tank.c
 
[Windows]
0=0000 tank.c 0 0 796 451 3 0
 
[Opened Files]
1=D:\KAKLIK\programy\PIC_C\roboti\merkur\PIC16F88\turn_R\tank.c
2=C:\Program Files\PICC\devices\16F88.h
3=
4=C:\Program Files\PICC\devices\16F88.h
5=
6=
7=
/roboti/istrobot/merkur/PIC16F88/turn_R/tank.SYM
0,0 → 1,88
003 STATUS
015-016 CCP_1
015 CCP_1_LOW
016 CCP_1_HIGH
020 @INTERRUPT_AREA
021 @INTERRUPT_AREA
022 @INTERRUPT_AREA
023 @INTERRUPT_AREA
024 @INTERRUPT_AREA
025 @INTERRUPT_AREA
026 @INTERRUPT_AREA
027 @INTERRUPT_AREA
028 @INTERRUPT_AREA
029-038 SendData
039.0 bit
03A fcslo
03B fcshi
03C stuff
03D flag_flag
03E fcs_flag
03F i
040 sensors
041 line
042 speed
043 rovinka
044 last
045 movement
046 dira
047-06E AXstring
06F-070 main.n
071-072 objizdka.n
071-072 diagnostika.n
071-072 prejeddiru.n
071 main.@SCRATCH
073 prejeddiru.speed_dira
073 diagnostika.@SCRATCH
073 objizdka.@SCRATCH
074-075 beep.period
074 @delay_ms1.P1
074-075 cikcak.n
074 prejeddiru.@SCRATCH
076 cikcak.@SCRATCH
077 @SCRATCH
078 @SCRATCH
078 _RETURN_
079 @SCRATCH
07A @SCRATCH
07B @SCRATCH
07C-07D beep.length
09C.6 C1OUT
09C.7 C2OUT
0A0-0A1 beep.nn
0A2 @delay_us1.P1
 
0088 @delay_ms1
0047 @delay_us1
0037 TIMER2_isr
005C beep
009D diagnostika
01FD cikcak
0289 objizdka
0386 prejeddiru
0472 main
0472 @cinit
01FD sem1
045C sem
 
Project Files:
D:\KAKLIK\programy\PIC_C\roboti\merkur\PIC16F88\turn_R\tank.c
D:\KAKLIK\programy\PIC_C\roboti\merkur\PIC16F88\turn_R\tank.h
C:\Program Files\PICC\devices\16F88.h
D:\KAKLIK\programy\PIC_C\roboti\merkur\PIC16F88\turn_R\AX25.c
 
Compiler Settings:
Processor: PIC16F88
Pointer Size: 8
ADC Range: 0-255
Opt Level: 9
Short,Int,Long: 1,8,16
 
Output Files:
Errors: D:\KAKLIK\programy\PIC_C\roboti\merkur\PIC16F88\turn_R\tank.err
INHX8: D:\KAKLIK\programy\PIC_C\roboti\merkur\PIC16F88\turn_R\tank.HEX
Symbols: D:\KAKLIK\programy\PIC_C\roboti\merkur\PIC16F88\turn_R\tank.SYM
List: D:\KAKLIK\programy\PIC_C\roboti\merkur\PIC16F88\turn_R\tank.LST
Debug/COFF: D:\KAKLIK\programy\PIC_C\roboti\merkur\PIC16F88\turn_R\tank.cof
Call Tree: D:\KAKLIK\programy\PIC_C\roboti\merkur\PIC16F88\turn_R\tank.tre
Statistics: D:\KAKLIK\programy\PIC_C\roboti\merkur\PIC16F88\turn_R\tank.sta
/roboti/istrobot/merkur/PIC16F88/turn_R/tank.c
0,0 → 1,339
#include "tank.h"
 
#define DEBUG
 
#define TXo PIN_A3 // To the transmitter modulator
#include "AX25.c" // podprogram pro prenos telemetrie
 
unsigned int8 sensors; // pomocna promenna pro cteni cidel na caru
unsigned int8 line; // na ktere strane byla detekovana cara
unsigned int8 speed; // rychlost zataceni
unsigned int8 rovinka; // pocitadlo pro zjisteni rovneho useku
unsigned int8 last; // kde byla cara, kdyz byly minule cidla mimo
unsigned int8 movement; // obsahuje aktualni smer zataceni
unsigned int8 dira; // pocita dobu po kterou je ztracena cara
 
// Konstanty pro dynamiku pohybu
#define T_DIRA 120 // po jakem case zataceni se detekuje dira
#define INC_SPEED 1 // prirustek rychlosti v jednom kroku
#define FW_POMALU 230 // trochu mimo caru vnitrni pas
#define FW_ZATACKA 240 // rychlost vnejsiho kola pri zataceni
#define FW_STREDNE 240 // trochu mimo caru vnejsi pas
#define COUVANI 750 // couvnuti zpet na caru, po detekci diry
#define PRES_DIRU 300
#define MAX_ROVINKA (255-FW_STREDNE)
#define TRESHOLD 6 // rozhodovaci uroven komparatoru, 0xF = 0.75*Vdd
#define BUMPER_TRESHOLD 128
#define CIK_CAK 30000
#define T_CIHLA 50 // perioda detekce cihly
 
//motory //Napred vypnout potom zapnout!
#define FR output_low(PIN_B5); output_high(PIN_B4) // Vpred
#define FL output_low(PIN_B7); output_high(PIN_B6)
#define BR output_low(PIN_B4); output_high(PIN_B5) // Vzad
#define BL output_low(PIN_B6); output_high(PIN_B7)
#define STOPR output_low(PIN_B4);output_low(PIN_B5) // Zastav
#define STOPL output_low(PIN_B6);output_low(PIN_B7)
 
#define L 0b10 // left
#define R 0b01 // right
#define S 0b11 // straight
 
//cidla
#define RSENSOR C2OUT // Senzory na caru
#define LSENSOR C1OUT
#define BUMPER PIN_A4 // Senzor na cihlu
 
#define DIAG_SERVO PIN_B3 // Propojka pro diagnosticky mod
#define DIAG_SENSORS PIN_B2 // Propojka pro diagnosticky mod
 
#DEFINE SOUND_HI PIN_A6 // komplementarni vystupy pro piezo pipak
#DEFINE SOUND_LO PIN_A7
 
char AXstring[40]; // Buffer pro prenos telemetrie
 
// makro pro PWM
#define GO(motor, direction, power) if(get_timer0()<=power) \
{direction##motor;} else {stop##motor;}
 
#int_TIMER2
void TIMER2_isr()
{
if (speed<255) speed+=INC_SPEED;
if (rovinka<MAX_ROVINKA) rovinka++;
if (dira<=T_DIRA) dira++;
}
// Primitivni Pipani
void beep(unsigned int16 period, unsigned int16 length)
{
unsigned int16 nn;
 
for(nn=length; nn>0; nn--)
{
output_high(SOUND_HI);output_low(SOUND_LO);
delay_us(period);
output_high(SOUND_LO);output_low(SOUND_HI);
delay_us(period);
}
}
/******************************************************************************/
void diagnostika()
{
unsigned int16 n;
 
while (input(DIAG_SERVO)) // Propojka, ktera spousti diagnostiku
{
for (n=500; n<800; n+=100)
{
beep(n,n); //beep UP
};
Delay_ms(1000);
//zastav vse
STOPL; STOPR;
//pravy pas
FR; Delay_ms(1000); STOPR; Delay_ms(1000);
BR; Delay_ms(1000); STOPR; Delay_ms(1000);
Beep(880,100); Delay_ms(1000);
//levy pas
FL; Delay_ms(1000); STOPL; Delay_ms(1000);
BL; Delay_ms(1000); STOPL; Delay_ms(1000);
Beep(880,100); Delay_ms(1000);
//oba pasy
FL; FR; Delay_ms(1000); STOPL; STOPR; Delay_ms(1000);
BL; BR; Delay_ms(1000); STOPL; STOPR; Delay_ms(1000);
};
while (input(DIAG_SENSORS)) // spusteni diagnostiky cidel
{
if (RSENSOR) beep(900,500);
if (LSENSOR) beep(800,500);
if ((read_adc(ADC_READ_ONLY)<BUMPER_TRESHOLD)) beep(1000,500);
};
}
///////////////////////////////////////////////////////////////////////////////
void cikcak()
{
unsigned int16 n;
sem1:
n=CIK_CAK;
while (0==RSENSOR||LSENSOR) // zkontroluj caru
{
if (n==CIK_CAK) // zmen smer zataceni
{
n=0;
switch(movement)
{
case L:
FL;BR;
movement=R;
break;
case R:
FR;BL;
movement=L;
break;
case S:
FL;BR;
movement=R;
n=CIK_CAK/2;
break;
}
}
n++;
}
STOPL;STOPR;
line = RSENSOR; // cteni senzoru na caru
line |= LSENSOR << 1;
if (line==0) goto sem1;
// nasli jsme caru
line=S;
}
///////////////////////////////////////////////////////////////////////////////
void objizdka() // objede cihlu
{
unsigned int16 n;
 
BL;BR;Delay_ms(150);
STOPR;STOPL;
beep(900,1000);
// movement=S;
// cikcak();
 
BR; FL; Delay_ms(270); // otoc se 70° do prava
 
FR; FL; Delay_ms(500); // popojed rovne
 
BL; Delay_ms(30); // otoc se 90° do leva
STOPL; FR; Delay_ms(500);
 
FR; FL; Delay_ms(100); // popojed rovne na slepo
for(n=40000;n>0;n--) // popojed rovne ale kontroluj caru
{
line = RSENSOR; // cteni senzoru na caru
line |= LSENSOR << 1;
if (line!=0) {Delay_ms(150); break;}
// Delay_ms(1);
}
 
BR; FL; // otoc se 60° do prava
for(n=40000;n>0;n--)
{
line = RSENSOR; // cteni senzoru na caru
line |= LSENSOR << 1;
if (line!=0) break;
// Delay_ms(1);
}
STOPR; STOPL;
 
movement=L; //R;
cikcak();
dira=0;
}
///////////////////////////////////////////////////////////////////////////////
void prejeddiru() // vyresi diru
{
unsigned int16 n;
unsigned int8 speed_dira;
 
STOPL;STOPR;
speed_dira=speed;
beep(1000,500);
switch (movement) //vrat se zpet na caru
{
case L:
for (n=COUVANI;n>0;n--) {GO(R,B,speed_dira); Delay_ms(1);}
STOPL;STOPR;
break;
case R:
for (n=COUVANI;n>0;n--) {GO(L,B,speed_dira); Delay_ms(1);}
STOPL;STOPR;
break;
case S:
goto sem;
break;
}
beep(1000,500);
 
/*line=0;
FR; BL; Delay_ms(400); // otoc se na caru
beep(1000,500);
while(line==0)
{
line = RSENSOR; // cteni senzoru na caru
line |= LSENSOR << 1;
}
FL;BR; Delay_ms(60); // zabrzdi
STOPL; STOPR;
 
FL; BR; Delay_ms(700); // otacka 180 deg
STOPL; STOPR;*/
 
FR;FL; //popojed rovne
for(n=PRES_DIRU;n>0;n--)
{
line = RSENSOR; // cteni senzoru na caru
line |= LSENSOR << 1;
if (line!=0) break;
Delay_ms(1);
}
sem:
STOPL; STOPR;
movement=S;
cikcak(); // najdi caru
dira=0;
}
///////////////////////////////////////////////////////////////////////////////
void main()
{
unsigned int16 n; // pro FOR
 
STOPL; STOPR; // prepne vystupy na ovladani motoru na output a zastavi
 
setup_oscillator(OSC_4MHZ|OSC_INTRC); // 4 MHz interni RC oscilator
 
port_b_pullups(TRUE); // pullups pro piano na diagnostiku
setup_spi(FALSE);
setup_timer_0(RTCC_INTERNAL|RTCC_DIV_1); // Casovac pro PWM
 
setup_timer_2(T2_DIV_BY_4,255,10); // Casovac pro regulaci
// preruseni kazdych 10ms
setup_adc_ports(sAN2|VSS_VDD); // nastaveni A/D prevodniku pro naraznik
setup_adc(ADC_CLOCK_INTERNAL);
set_adc_channel(2);
setup_timer_1(T1_INTERNAL|T1_DIV_BY_1); // Casovac pro naraznik
setup_ccp1(CCP_COMPARE_RESET_TIMER);
CCP_1=(2^10)-1; // prevod kazdou 1ms
 
setup_comparator(A0_VR_A1_VR); // inicializace komparatoru pro cidla cary
setup_vref(VREF_HIGH|TRESHOLD); // 32 kroku od 0.25 do 0.75 Vdd
 
Beep(1000,200); //double beep
Delay_ms(50);
Beep(1000,200);
Delay_ms(1000); // 1s
 
// povoleni rizeni rychlosti zataceni pres preruseni
enable_interrupts(INT_TIMER2);
enable_interrupts(GLOBAL);
 
/*---------------------------------------------------------------------------*/
sensors=S;
line=S;
last=S;
movement=S;
speed=FW_POMALU;
 
diagnostika();
//cikcak(); // toc se, abys nasel caru
Delay_ms(500);
Beep(1000,200);
Delay_ms(500);
 
while(true) // hlavni smycka (jizda podle cary)
{
sensors = RSENSOR; // cteni senzoru na caru
sensors |= LSENSOR << 1;
 
if ((read_adc(ADC_READ_ONLY)<BUMPER_TRESHOLD) && (dira<=T_CIHLA)) objizdka();
 
switch (sensors) // zatacej podle toho, kde vidis caru
{
case S: // rovne
FL; FR; // pokud se jede dlouho rovne, tak pridej
dira=0;
movement=S;
continue;
case L: // trochu vlevo
GO(L, F, FW_POMALU+rovinka); GO(R, F, FW_STREDNE+rovinka);
line=L;
dira=0;
movement=L;
continue;
case R: // trochu vpravo
GO(R, F, FW_POMALU+rovinka); GO(L, F, FW_STREDNE+rovinka);
line=R;
dira=0;
movement=R;
continue;
default: // kdyz jsou obe cidla mimo caru, tak pokracuj dal
}
rovinka=0;
if (dira>=T_DIRA) prejeddiru();
if (last!=line) // pokud si prejel caru z jedne strany na druhou stranu, tak zabrzdi
{
last=line;
speed=FW_ZATACKA;
}
if (L==line) // kdyz jsou obe cidla mimo caru, zatoc na caru
{
STOPL;
GO(R, F, speed);
movement=L;
}
else
{
STOPR;
GO(L, F, speed);
movement=R;
}
} // while(true)
}
 
/roboti/istrobot/merkur/PIC16F88/turn_R/tank.cof
Cannot display: file marked as a binary type.
svn:mime-type = application/octet-stream
Property changes:
Added: svn:mime-type
+application/octet-stream
\ No newline at end of property
/roboti/istrobot/merkur/PIC16F88/turn_R/tank.err
0,0 → 1,0
No Errors
/roboti/istrobot/merkur/PIC16F88/turn_R/tank.h
0,0 → 1,5
#include <16F88.h>
#device adc=8
#fuses NOWDT,INTRC_IO, NOPUT, MCLR, NOBROWNOUT, NOLVP, NOCPD, NOWRT, NODEBUG, NOPROTECT, NOFCMEN, NOIESO
#use delay(clock=4000000)
 
/roboti/istrobot/merkur/PIC16F88/turn_R/tank.sta
0,0 → 1,38
 
ROM used: 1587 (39%)
1587 (39%) including unused fragments
 
2 Average locations per line
4 Average locations per statement
 
RAM used: 87 (50%) at main() level
98 (56%) worst case
 
Lines Stmts % Files
----- ----- --- -----
340 357 84 D:\KAKLIK\programy\PIC_C\roboti\merkur\PIC16F88\turn_R\tank.c
6 0 0 D:\KAKLIK\programy\PIC_C\roboti\merkur\PIC16F88\turn_R\tank.h
275 0 0 C:\Program Files\PICC\devices\16F88.h
136 67 9 D:\KAKLIK\programy\PIC_C\roboti\merkur\PIC16F88\turn_R\AX25.c
----- -----
1514 848 Total
 
Page ROM % RAM Functions:
---- --- --- --- ----------
0 21 1 1 @delay_ms1
0 21 1 1 @delay_us1
0 16 1 0 TIMER2_isr
0 44 3 6 beep
0 352 22 3 diagnostika
0 140 9 3 cikcak
0 253 16 3 objizdka
0 236 15 4 prejeddiru
0 449 28 3 main
 
Segment Used Free
--------- ---- ----
00000-00003 4 0
00004-00036 51 0
00037-007FF 1532 461
00800-00FFF 0 2048
 
/roboti/istrobot/merkur/PIC16F88/turn_R/tank.tre
0,0 → 1,74
ÀÄtank
ÃÄmain 0/449 Ram=3
³ ÃÄ??0??
³ ÃÄbeep 0/44 Ram=6
³ ³ ÃÄ@delay_us1 0/21 Ram=1
³ ³ ÀÄ@delay_us1 0/21 Ram=1
³ ÃÄ@delay_ms1 0/21 Ram=1
³ ÃÄbeep 0/44 Ram=6
³ ³ ÃÄ@delay_us1 0/21 Ram=1
³ ³ ÀÄ@delay_us1 0/21 Ram=1
³ ÃÄ@delay_ms1 0/21 Ram=1
³ ÃÄdiagnostika 0/352 Ram=3
³ ³ ÃÄbeep 0/44 Ram=6
³ ³ ³ ÃÄ@delay_us1 0/21 Ram=1
³ ³ ³ ÀÄ@delay_us1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄbeep 0/44 Ram=6
³ ³ ³ ÃÄ@delay_us1 0/21 Ram=1
³ ³ ³ ÀÄ@delay_us1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄbeep 0/44 Ram=6
³ ³ ³ ÃÄ@delay_us1 0/21 Ram=1
³ ³ ³ ÀÄ@delay_us1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄbeep 0/44 Ram=6
³ ³ ³ ÃÄ@delay_us1 0/21 Ram=1
³ ³ ³ ÀÄ@delay_us1 0/21 Ram=1
³ ³ ÃÄbeep 0/44 Ram=6
³ ³ ³ ÃÄ@delay_us1 0/21 Ram=1
³ ³ ³ ÀÄ@delay_us1 0/21 Ram=1
³ ³ ÀÄbeep 0/44 Ram=6
³ ³ ÃÄ@delay_us1 0/21 Ram=1
³ ³ ÀÄ@delay_us1 0/21 Ram=1
³ ÃÄ@delay_ms1 0/21 Ram=1
³ ÃÄbeep 0/44 Ram=6
³ ³ ÃÄ@delay_us1 0/21 Ram=1
³ ³ ÀÄ@delay_us1 0/21 Ram=1
³ ÃÄ@delay_ms1 0/21 Ram=1
³ ÃÄobjizdka 0/253 Ram=3
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄbeep 0/44 Ram=6
³ ³ ³ ÃÄ@delay_us1 0/21 Ram=1
³ ³ ³ ÀÄ@delay_us1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÀÄcikcak 0/140 Ram=3
³ ÀÄprejeddiru 0/236 Ram=4
³ ÃÄbeep 0/44 Ram=6
³ ³ ÃÄ@delay_us1 0/21 Ram=1
³ ³ ÀÄ@delay_us1 0/21 Ram=1
³ ÃÄ@delay_ms1 0/21 Ram=1
³ ÃÄ@delay_ms1 0/21 Ram=1
³ ÃÄbeep 0/44 Ram=6
³ ³ ÃÄ@delay_us1 0/21 Ram=1
³ ³ ÀÄ@delay_us1 0/21 Ram=1
³ ÃÄ@delay_ms1 0/21 Ram=1
³ ÀÄcikcak 0/140 Ram=3
ÀÄTIMER2_isr 0/16 Ram=0
/roboti/istrobot/merkur/PIC16F88/turn_R/verze/1 tank.c
0,0 → 1,313
#include "tank.h"
 
#define TXo PIN_B1 // To the transmitter modulator
#include "AX25.c" // podprogram pro prenos telemetrie
 
//motory //Napred vypnout potom zapnout!
#define FR output_low(PIN_B5); output_high(PIN_B4) // Vpred
#define FL output_low(PIN_B7); output_high(PIN_B6)
#define BR output_low(PIN_B4); output_high(PIN_B5) // Vzad
#define BL output_low(PIN_B6); output_high(PIN_B7)
#define STOPR output_low(PIN_B4);output_low(PIN_B5)
#define STOPL output_low(PIN_B6);output_low(PIN_B7)
 
#define L 0b10 // left
#define R 0b01 // right
#define S 0b11 // straight
 
#define COUVANI 1600 // couvnuti po zjisteni diry
#define MEZERA 5400 // za jak dlouho bude ztracena cara
#define PRES_DIRU 1000 // velikost mezery v care
#define BRZDENI 5000 // doba ptrebna k zastaveni jednoho motoru
 
//cidla
#define RSENSOR C2OUT // Senzory na caru
#define LSENSOR C1OUT
#define BUMPER PIN_A4 // sensor na cihlu
 
#define DIAG_SERVO PIN_B2 // Propojka pro diagnosticky mod
#define DIAG_SENSORS PIN_B3 // Propojka pro diagnosticky mod
 
#DEFINE SOUND_HI PIN_A7
#DEFINE SOUND_LO PIN_A6
 
char AXstring[40]; // Buffer pro prenos telemetrie
 
#define GO(motor, direction, power) if(get_timer0()<=power) \
{direction##motor;} \
else \
{stop##motor;}
 
int movement; // smer minuleho pohybu
int line; // na ktere strane byla detekovana cara
unsigned int16 dira; // pocitadlo pro nalezeni preruseni cary
int speed,speedL,speedR;
 
// Primitivni Pipani
void beep(unsigned int16 period, unsigned int16 length)
{
unsigned int16 nn;
 
for(nn=length; nn>0; nn--)
{
output_high(SOUND_HI);output_low(SOUND_LO);
delay_us(period);
output_high(SOUND_LO);output_low(SOUND_HI);
delay_us(period);
}
}
#int_TIMER2
void TIMER2_isr()
{
switch(line) // upravime smer
{
case S: //obe cidla na care
if(speedL<200)speedL++;
if(speedR<200)speedR++;
break; // vrat se zpet na cteni cidel
case L: // cara je pod levym cidlem, trochu zatocime
if (speedL>100)speedL -- ;
if (speedR<200)speedR ++ ;
break;
case R: // cara pod pravym cidlem
if (speedR>100)speedR -- ;
if (speedL<200)speedL ++ ;
break;
default:
}
}
// Diagnostika pohonu, hejbne vsema motorama ve vsech smerech
void diagnostika()
{
unsigned int16 n;
 
while (input(DIAG_SERVO)) // Propojka, ktera spousti diagnostiku
{
for (n=500; n<800; n+=100)
{
beep(n,n); //beep UP
};
Delay_ms(1000);
//zastav vse
STOPL; STOPR;
//pravy pas
FR; Delay_ms(1000); STOPR; Delay_ms(1000);
BR; Delay_ms(1000); STOPR; Delay_ms(1000);
Beep(880,100); Delay_ms(1000);
//levy pas
FL; Delay_ms(1000); STOPL; Delay_ms(1000);
BL; Delay_ms(1000); STOPL; Delay_ms(1000);
Beep(880,100); Delay_ms(1000);
//oba pasy
FL; FR; Delay_ms(1000); STOPL; STOPR; Delay_ms(1000);
BL; BR; Delay_ms(1000); STOPL; STOPR; Delay_ms(1000);
};
 
while (input(DIAG_SENSORS))
{
int ls, rs;
while(!input(BUMPER)){beep(1100,100); Delay_ms(50);}
set_adc_channel(RSENSOR);
Delay_us(20);
rs=read_adc();
set_adc_channel(LSENSOR);
Delay_us(20);
ls=read_adc();
sprintf(AXstring,"L: %U R: %U\0", ls, rs); // Convert DATA to String.
SendPacket(&AXstring[0]);
delay_ms(1000);
};
}
 
void cikcak()
{
int n;
switch(movement) // podivej se na jednu stranu
{
case L:
FL;BR;
movement=R;
break;
case R:
FR;BL;
movement=L;
break;
case S:
FR;BL;
movement=L;
break;
}
while (0==(RSENSOR|LSENSOR))
{
if (n==50) // asi bude na druhe strane
{
STOPR;STOPL;
n=0;
switch(movement)
{
case L:
FL;BR;
movement=R;
break;
case R:
FR;BL;
movement=L;
break;
}
}
Delay_ms(5);
n++;
}
STOPL;STOPR; // nasli jsme caru
line=S;
}
void objizdka()
{
BL;BR;Delay_ms(300);
STOPR;STOPL;
beep(1000,1000);
Delay_ms(500);
beep(1000,1000);
Delay_ms(1000);
 
 
 
}
 
void pozordira()
{
beep(800,500);
Delay_ms(50);
beep(800,500);
switch (movement) //vrat se zpet na caru
{
case L:
STOPL;STOPR;
BR;Delay_ms(COUVANI);STOPR;
break;
case R:
STOPL;STOPR;
BL;Delay_ms(COUVANI);STOPL;
break;
case S:
BL; BR; Delay_ms(COUVANI);
STOPL; STOPR;
break;
}
 
FR;FL; Delay_ms(PRES_DIRU); // popojedem dopredu mozna tam bude cara
STOPL; STOPR; movement=S;
cikcak(); // najdi caru
dira=0;
}
 
void main()
{
unsigned int16 rovinka;
int last;
 
STOPL; STOPR;
 
setup_oscillator(OSC_4MHZ|OSC_INTRC); // 4 MHz interni RC oscilator
port_b_pullups(true);
setup_adc_ports(NO_ANALOGS|VSS_VDD);
setup_adc(ADC_OFF);
setup_spi(FALSE);
setup_timer_0(RTCC_INTERNAL|RTCC_DIV_1); // Casovac pro PWM
setup_timer_1(T1_DISABLED); // Casovac pro regulaci
setup_timer_2(T2_DIV_BY_16,50,16);
setup_ccp1(CCP_OFF);
setup_comparator(A0_VR_A1_VR);
setup_vref(VREF_HIGH|15);
enable_interrupts(INT_TIMER2);
enable_interrupts(GLOBAL);
 
diagnostika();
 
Beep(1000,200); //double beep
Delay_ms(50);
Beep(1000,200);
Delay_ms(1000); // 1s
 
// FL; FR;
movement=S;
line=S;
dira=0;
last=0;
rovinka=0;
 
speed=speedL=speedR=200;
 
while(true)
{
line = RSENSOR; // precteni cidel
line |= LSENSOR << 1; // sestav informaci o care
if(line!=0)
{
GO(L, F, speedL); GO(R,F, speedR);
}
else{STOPR; STOPL;}
//sem:
/* switch(line) // upravime smer
{
case S: //obe cidla na care
// if (speedL<speedR) speedL=speedR;
// else speedR=speedL;
GO(L,F,speedL); GO(R,F,speedR) // jedeme rovne
// if(rovinka<BRZDENI) rovinka++; //cara je rovne
// dira=0; // videli jsme caru, proto neni dira
continue; // vrat se zpet na cteni cidel
case L: // cara je pod levym cidlem, trochu zatocime
GO(L, F, speedL); GO(R,F, speedR);
// if(rovinka<BRZDENI) rovinka++; //cara je celkem rovne
// dira=0;
continue;
case R: // cara pod pravym cidlem
GO(R, F, speedR); GO(L, F, speedL);
// if(rovinka<BRZDENI) rovinka++;
// dira=0;
continue;
default: // cara neni pod zadnym cidlem
}*/
 
 
/*switch (last) // zatacka
{
case L: // do leva
BL;STOPR; //zabrzdeni leveho motoru
for(;rovinka>0;rovinka--) //chvili pockej
{
line = RSENSOR; // precteni cidel
line |= LSENSOR << 1; // sestav informaci o care
if(line!=0) goto sem; //kdyz najdes caru, zastav
}
STOPL; FR; // pokracuj v zataceni
while(line==0)
{
line = RSENSOR; // precteni cidel
line |= LSENSOR << 1; // sestav informaci o care
}
movement=L;
rovinka=0; //zataceli jsme, uz neni rovna cara
break;
case R:
BR; STOPL; // zabrzdeni praveho motoru
for(;rovinka>0;rovinka--)
{
line = RSENSOR; // precteni cidel
line |= LSENSOR << 1; // sestav informaci o care
if(line!=0) goto sem;
}
STOPR; FL;
while(line==0)
{
line = RSENSOR; // precteni cidel
line |= LSENSOR << 1; // sestav informaci o care
}
movement=R;
rovinka=0; //zataceli jsme, uz neni rovna cara
break;
}*/
} // while(true)
}
/roboti/istrobot/merkur/PIC16F88/turn_R/verze/2 tank.c
0,0 → 1,331
#include "tank.h"
 
#define DEBUG
 
#define TXo PIN_A3 // To the transmitter modulator
#include "AX25.c" // podprogram pro prenos telemetrie
 
unsigned int8 sensors; // pomocna promenna pro cteni cidel na caru
unsigned int8 line; // na ktere strane byla detekovana cara
unsigned int8 speed; // rychlost zataceni
unsigned int8 rovinka; // pocitadlo pro zjisteni rovneho useku
unsigned int8 last; // kde byla cara, kdyz byly minule cidla mimo
unsigned int8 movement; // obsahuje aktualni smer zataceni
unsigned int8 dira; // pocita dobu po kterou je ztracena cara
 
// Konstanty pro dynamiku pohybu
#define T_DIRA 100 // po jakem case zataceni se detekuje dira
#define INC_SPEED 1 // prirustek rychlosti v jednom kroku
#define FW_POMALU 100 // trochu mimo caru vnitrni pas
#define FW_ZATACKA 200 // rychlost vnejsiho kola pri zataceni
#define FW_STREDNE 110 // trochu mimo caru vnejsi pas
#define COUVANI 600 // couvnuti zpet na caru, po detekci diry
#define PRES_DIRU 300
#define MAX_ROVINKA (255-FW_STREDNE)
#define TRESHOLD 6 // rozhodovaci uroven komparatoru, 0xF = 0.75*Vdd
 
//motory //Napred vypnout potom zapnout!
#define FR output_low(PIN_B5); output_high(PIN_B4) // Vpred
#define FL output_low(PIN_B7); output_high(PIN_B6)
#define BR output_low(PIN_B4); output_high(PIN_B5) // Vzad
#define BL output_low(PIN_B6); output_high(PIN_B7)
#define STOPR output_low(PIN_B4);output_low(PIN_B5) // Zastav
#define STOPL output_low(PIN_B6);output_low(PIN_B7)
 
#define L 0b10 // left
#define R 0b01 // right
#define S 0b11 // straight
 
//cidla
#define RSENSOR C2OUT // Senzory na caru
#define LSENSOR C1OUT
#define BUMPER PIN_A4 // Senzor na cihlu
 
#define DIAG_SERVO PIN_B3 // Propojka pro diagnosticky mod
#define DIAG_SENSORS PIN_B2 // Propojka pro diagnosticky mod
 
#DEFINE SOUND_HI PIN_A6 // komplementarni vystupy pro piezo pipak
#DEFINE SOUND_LO PIN_A7
 
char AXstring[40]; // Buffer pro prenos telemetrie
 
// makro pro PWM
#define GO(motor, direction, power) if(get_timer0()<=power) \
{direction##motor;} \
else \
{stop##motor;}
 
#int_TIMER2
void TIMER2_isr()
{
if (speed<255) speed+=INC_SPEED;
if (rovinka<MAX_ROVINKA) rovinka++;
if (dira<T_DIRA) dira++;
}
 
// Primitivni Pipani
void beep(unsigned int16 period, unsigned int16 length)
{
unsigned int16 nn;
 
for(nn=length; nn>0; nn--)
{
output_high(SOUND_HI);output_low(SOUND_LO);
delay_us(period);
output_high(SOUND_LO);output_low(SOUND_HI);
delay_us(period);
}
}
/******************************************************************************/
void diagnostika()
{
unsigned int16 n;
 
while (input(DIAG_SERVO)) // Propojka, ktera spousti diagnostiku
{
for (n=500; n<800; n+=100)
{
beep(n,n); //beep UP
};
Delay_ms(1000);
//zastav vse
STOPL; STOPR;
//pravy pas
FR; Delay_ms(1000); STOPR; Delay_ms(1000);
BR; Delay_ms(1000); STOPR; Delay_ms(1000);
Beep(880,100); Delay_ms(1000);
//levy pas
FL; Delay_ms(1000); STOPL; Delay_ms(1000);
BL; Delay_ms(1000); STOPL; Delay_ms(1000);
Beep(880,100); Delay_ms(1000);
//oba pasy
FL; FR; Delay_ms(1000); STOPL; STOPR; Delay_ms(1000);
BL; BR; Delay_ms(1000); STOPL; STOPR; Delay_ms(1000);
};
 
while (input(DIAG_SENSORS))
{
int ls, rs;
while(!input(BUMPER)){beep(1100,100); Delay_ms(50);}
set_adc_channel(RSENSOR);
Delay_us(20);
rs=read_adc();
set_adc_channel(LSENSOR);
Delay_us(20);
ls=read_adc();
sprintf(AXstring,"L: %U R: %U\0", ls, rs); // Convert DATA to String.
SendPacket(&AXstring[0]);
delay_ms(1000);
};
}
///////////////////////////////////////////////////////////////////////////////
void cikcak()
{
int n;
switch(movement) // podivej se na jednu stranu
{
case L:
FL;BR;
movement=R;
break;
case R:
FR;BL;
movement=L;
break;
case S:
FR;BL;
movement=L;
break;
}
while (0==(RSENSOR|LSENSOR))
{
if (n==50) //cara asi bude na druhe strane
{
STOPR;STOPL;
n=0;
switch(movement)
{
case L:
FL;BR;
movement=R;
break;
case R:
FR;BL;
movement=L;
break;
}
}
Delay_ms(5);
n++;
}
STOPL;STOPR; // nasli jsme caru
line=S;
}
///////////////////////////////////////////////////////////////////////////////
void objizdka()
{
BL;BR;Delay_ms(300);
STOPR;STOPL;
beep(1000,1000);
Delay_ms(500);
beep(1000,1000);
Delay_ms(1000);
 
 
 
}
///////////////////////////////////////////////////////////////////////////////
void prejeddiru()
{
STOPL;STOPR;
beep(800,500);
Delay_ms(50);
beep(800,500);
switch (movement) //vrat se zpet na caru
{
case L:
BR;Delay_ms(COUVANI);STOPR;
STOPL;STOPR;
break;
case R:
 
BL;Delay_ms(COUVANI);STOPL;
STOPL;STOPR;
break;
case S:
BL; BR; Delay_ms(COUVANI);
STOPL; STOPR;
break;
}
 
FR;FL; Delay_ms(PRES_DIRU); // popojedem dopredu mozna tam bude cara
STOPL; STOPR;
cikcak(); // najdi caru
dira=0;
}
///////////////////////////////////////////////////////////////////////////////
void main()
{
unsigned int16 n; // pro FOR
 
STOPL; STOPR; // prepne vystupy na ovladani motoru na output a zastavi
 
setup_oscillator(OSC_4MHZ|OSC_INTRC); // 4 MHz interni RC oscilator
 
port_b_pullups(TRUE); // pullups pro piano na diagnostiku
setup_spi(FALSE);
setup_timer_0(RTCC_INTERNAL|RTCC_DIV_1); // Casovac pro PWM
 
setup_timer_2(T2_DIV_BY_16,255,10); // Casovac pro regulaci
// preruseni kazdych 10ms
setup_adc_ports(sAN2|VSS_VDD); // nastaveni A/D prevodniku pro naraznik
setup_adc(ADC_CLOCK_INTERNAL);
set_adc_channel(2);
setup_timer_1(T1_INTERNAL|T1_DIV_BY_1); // Casovac pro naraznik
setup_ccp1(CCP_COMPARE_RESET_TIMER);
CCP_1=(2^10)-1; // prevod kazdou 1ms
 
setup_comparator(A0_VR_A1_VR); // inicializace komparatoru pro cidla cary
setup_vref(VREF_HIGH|TRESHOLD); // 32 kroku od 0.25 do 0.75 Vdd
 
Beep(1000,200); //double beep
Delay_ms(50);
Beep(1000,200);
Delay_ms(1000); // 1s
 
// povoleni rizeni rychlosti zataceni pres preruseni
enable_interrupts(INT_TIMER2);
enable_interrupts(GLOBAL);
 
/*---------------------------------------------------------------------------*/
sensors=S;
line=S;
last=S;
movement=S;
speed=FW_POMALU;
 
diagnostika();
cikcak(); // toc se, abys nasel caru
Delay_ms(500);
Beep(1000,200);
Delay_ms(500);
 
while(true) // hlavni smycka (jizda podle cary)
{
 
sensors = RSENSOR; // cteni senzoru na caru
sensors |= LSENSOR << 1;
 
switch (sensors) // zatacej podle toho, kde vidis caru
{
case S: // rovne
GO(L, F, speed); GO(R, F, speed);
// FL; FR; // pokud se jede dlouho rovne, tak pridej
dira=0;
continue;
 
case L: // trochu vlevo
GO(L, F, FW_POMALU+rovinka); GO(R, F, FW_STREDNE+rovinka);
line=L;
dira=0;
continue;
 
case R: // trochu vpravo
GO(R, F, FW_POMALU+rovinka); GO(L, F, FW_STREDNE+rovinka);
line=R;
dira=0;
continue;
 
default: // kdyz jsou obe cidla mimo caru, tak pokracuj dal
}
rovinka=0;
// if (dira>=T_DIRA) prejeddiru();
if (last!=line) // pokud si prejel caru z jedne strany na druhou stranu, tak zabrzdi
{
last=line;
speed=FW_ZATACKA;
}
else speed=255;
/* if (dira==0)
{
if (L==line) // kdyz jsou obe cidla mimo caru, zabrzdi vnitrni kolo
{
BL;
for(n=4000;n>0;n--) // Delay
{
line = RSENSOR; // precteni cidel
line |= LSENSOR << 1; // sestav informaci o care
if(line!=0) break;
}
STOPL;
}
else
{
BR;
for(n=4000;n>0;n--) // Delay
{
line = RSENSOR; // precteni cidel
line |= LSENSOR << 1; // sestav informaci o care
if(line!=0) break;
}
STOPR;
}
}*/
if (L==line) // kdyz jsou obe cidla mimo caru, zatoc na caru
{
STOPL;
GO(R, F, speed);
movement=L;
}
else
{
STOPR;
GO(L, F, speed);
movement=R;
}
} // while(true)
}
 
/roboti/istrobot/merkur/PIC16F88/turn_R/verze/tank_funkcni.BAK
0,0 → 1,352
#include "tank.h"
 
#define DEBUG
 
#define TXo PIN_A3 // To the transmitter modulator
#include "AX25.c" // podprogram pro prenos telemetrie
 
unsigned int8 sensors; // pomocna promenna pro cteni cidel na caru
unsigned int8 line; // na ktere strane byla detekovana cara
unsigned int8 speed; // rychlost zataceni
unsigned int8 rovinka; // pocitadlo pro zjisteni rovneho useku
unsigned int8 last; // kde byla cara, kdyz byly minule cidla mimo
unsigned int8 movement; // obsahuje aktualni smer zataceni
unsigned int8 dira; // pocita dobu po kterou je ztracena cara
unsigned int8 cihla; // urcuje za jak dlouho muze byt znova detekovana cihla
 
// Konstanty pro dynamiku pohybu
#define T_DIRA 87 // po jakem case zataceni se detekuje dira
#define INC_SPEED 1 // prirustek rychlosti v jednom kroku
#define FW_POMALU 230 // trochu mimo caru vnitrni pas
#define FW_ZATACKA 200 // rychlost vnejsiho kola pri zataceni
#define FW_STREDNE 240 // trochu mimo caru vnejsi pas
#define COUVANI 600 // couvnuti zpet na caru, po detekci diry
#define PRES_DIRU 250
#define MAX_ROVINKA (255-FW_STREDNE)
#define TRESHOLD 10 // rozhodovaci uroven komparatoru, 0xF = 0.75*Vdd
#define BUMPER_TRESHOLD 128
#define CIK_CAK 30000
#define T_CIHLA 100 // perioda detekce cihly
 
//motory //Napred vypnout potom zapnout!
#define FR output_low(PIN_B5); output_high(PIN_B4) // Vpred
#define FL output_low(PIN_B7); output_high(PIN_B6)
#define BR output_low(PIN_B4); output_high(PIN_B5) // Vzad
#define BL output_low(PIN_B6); output_high(PIN_B7)
#define STOPR output_low(PIN_B4);output_low(PIN_B5) // Zastav
#define STOPL output_low(PIN_B6);output_low(PIN_B7)
 
#define L 0b10 // left
#define R 0b01 // right
#define S 0b11 // straight
 
//cidla
#define RSENSOR C2OUT // Senzory na caru
#define LSENSOR C1OUT
#define BUMPER PIN_A4 // Senzor na cihlu
 
#define DIAG_SERVO PIN_B3 // Propojka pro diagnosticky mod
#define DIAG_SENSORS PIN_B2 // Propojka pro diagnosticky mod
 
#DEFINE SOUND_HI PIN_A6 // komplementarni vystupy pro piezo pipak
#DEFINE SOUND_LO PIN_A7
 
char AXstring[40]; // Buffer pro prenos telemetrie
 
// makro pro PWM
#define GO(motor, direction, power) if(get_timer0()<=power) \
{direction##motor;} else {stop##motor;}
 
#int_TIMER2
void TIMER2_isr()
{
if (speed<255) speed+=INC_SPEED;
if (rovinka<MAX_ROVINKA) rovinka++;
if (dira<=T_DIRA) dira++;
if (cihla>0) cihla--;
}
// Primitivni Pipani
void beep(unsigned int16 period, unsigned int16 length)
{
unsigned int16 nn;
 
for(nn=length; nn>0; nn--)
{
output_high(SOUND_HI);output_low(SOUND_LO);
delay_us(period);
output_high(SOUND_LO);output_low(SOUND_HI);
delay_us(period);
}
}
/******************************************************************************/
void diagnostika()
{
unsigned int16 n;
 
while (input(DIAG_SERVO)) // Propojka, ktera spousti diagnostiku
{
for (n=500; n<800; n+=100)
{
beep(n,n); //beep UP
};
Delay_ms(1000);
//zastav vse
STOPL; STOPR;
//pravy pas
FR; Delay_ms(1000); STOPR; Delay_ms(1000);
BR; Delay_ms(1000); STOPR; Delay_ms(1000);
Beep(880,100); Delay_ms(1000);
//levy pas
FL; Delay_ms(1000); STOPL; Delay_ms(1000);
BL; Delay_ms(1000); STOPL; Delay_ms(1000);
Beep(880,100); Delay_ms(1000);
//oba pasy
FL; FR; Delay_ms(1000); STOPL; STOPR; Delay_ms(1000);
BL; BR; Delay_ms(1000); STOPL; STOPR; Delay_ms(1000);
};
while (input(DIAG_SENSORS))
{
int ls, rs;
while(!input(BUMPER)){beep(1100,100); Delay_ms(50);}
set_adc_channel(RSENSOR);
Delay_us(20);
rs=read_adc();
set_adc_channel(LSENSOR);
Delay_us(20);
ls=read_adc();
sprintf(AXstring,"L: %U R: %U\0", ls, rs); // Convert DATA to String.
SendPacket(&AXstring[0]);
delay_ms(1000);
};
}
///////////////////////////////////////////////////////////////////////////////
void cikcak()
{
unsigned int16 n;
sem1:
n=CIK_CAK;
while (0==RSENSOR) // zkontroluj caru
{
if (n==CIK_CAK) // zmen smer zataceni
{
n=0;
switch(movement)
{
case L:
FL;BR;
movement=R;
break;
case R:
FR;BL;
movement=L;
break;
case S:
FL;BR;
movement=R;
n=CIK_CAK/2;
break;
}
}
n++;
}
STOPL;STOPR;
line = RSENSOR; // cteni senzoru na caru
line |= LSENSOR << 1;
if (line==0) goto sem1;
// nasli jsme caru
line=S;
}
///////////////////////////////////////////////////////////////////////////////
void objizdka() // objede cihlu
{
unsigned int16 n;
 
BL;BR;Delay_ms(200);
STOPR;STOPL;
beep(900,1000);
// movement=S;
// cikcak();
 
BR; FL; Delay_ms(215); // otoc se 70° do prava
 
FR; FL; Delay_ms(600); // popojed rovne
 
BL; Delay_ms(30); // otoc se 90° do leva
STOPL; FR; Delay_ms(600);
 
FR; FL; Delay_ms(100); // popojed rovne na slepo
for(n=600;n>0;n--) // popojed rovne ale kontroluj caru
{
line = RSENSOR; // cteni senzoru na caru
line |= LSENSOR << 1;
if (line!=0) {Delay_ms(50); break;}
Delay_ms(1);
}
 
BR; // otoc se 60° do prava
for(n=600;n>0;n--)
{
line = RSENSOR; // cteni senzoru na caru
line |= LSENSOR << 1;
if (line!=0) break;
Delay_ms(1);
}
STOPR; STOPL;
 
movement=R;
cikcak();
cihla=T_CIHLA;
dira=0;
}
///////////////////////////////////////////////////////////////////////////////
void prejeddiru() // vyresi diru
{
unsigned int16 n;
unsigned int8 speed_dira;
 
STOPL;STOPR;
speed_dira=speed;
beep(1000,500);
switch (movement) //vrat se zpet na caru
{
case L:
for (n=COUVANI;n>0;n--) {GO(R,B,speed_dira); Delay_ms(1);}
STOPL;STOPR;
break;
case R:
for (n=COUVANI;n>0;n--) {GO(L,B,speed_dira); Delay_ms(1);}
STOPL;STOPR;
break;
case S:
goto sem;
break;
}
beep(800,500);
line=0;
FR; BL; Delay_ms(300); // otoc se na caru
while(line==0)
{
line = RSENSOR; // cteni senzoru na caru
line |= LSENSOR << 1;
}
FL;BR; Delay_ms(60);
STOPL; STOPR;
FL; BR; Delay_ms(500);
STOPL; STOPR;
Delay_ms(1000);
FR;FL; //popojed rovne
for(n=PRES_DIRU;n>0;n--)
{
line = RSENSOR; // cteni senzoru na caru
line |= LSENSOR << 1;
if (line!=0) break;
Delay_ms(1);
}
sem:
STOPL; STOPR;
movement=S;
cikcak(); // najdi caru
cihla=T_CIHLA;
dira=0;
}
///////////////////////////////////////////////////////////////////////////////
void main()
{
unsigned int16 n; // pro FOR
 
STOPL; STOPR; // prepne vystupy na ovladani motoru na output a zastavi
 
setup_oscillator(OSC_4MHZ|OSC_INTRC); // 4 MHz interni RC oscilator
 
port_b_pullups(TRUE); // pullups pro piano na diagnostiku
setup_spi(FALSE);
setup_timer_0(RTCC_INTERNAL|RTCC_DIV_1); // Casovac pro PWM
 
setup_timer_2(T2_DIV_BY_4,255,10); // Casovac pro regulaci
// preruseni kazdych 10ms
setup_adc_ports(sAN2|VSS_VDD); // nastaveni A/D prevodniku pro naraznik
setup_adc(ADC_CLOCK_INTERNAL);
set_adc_channel(2);
setup_timer_1(T1_INTERNAL|T1_DIV_BY_1); // Casovac pro naraznik
setup_ccp1(CCP_COMPARE_RESET_TIMER);
CCP_1=(2^10)-1; // prevod kazdou 1ms
 
setup_comparator(A0_VR_A1_VR); // inicializace komparatoru pro cidla cary
setup_vref(VREF_HIGH|TRESHOLD); // 32 kroku od 0.25 do 0.75 Vdd
 
Beep(1000,200); //double beep
Delay_ms(50);
Beep(1000,200);
Delay_ms(1000); // 1s
 
// povoleni rizeni rychlosti zataceni pres preruseni
enable_interrupts(INT_TIMER2);
enable_interrupts(GLOBAL);
 
/*---------------------------------------------------------------------------*/
sensors=S;
line=S;
last=S;
movement=S;
speed=FW_POMALU;
 
diagnostika();
// cikcak(); // toc se, abys nasel caru
Delay_ms(500);
Beep(1000,200);
Delay_ms(500);
 
while(true) // hlavni smycka (jizda podle cary)
{
sensors = RSENSOR; // cteni senzoru na caru
sensors |= LSENSOR << 1;
 
if ((read_adc(ADC_READ_ONLY)<BUMPER_TRESHOLD) && (cihla==0)) objizdka();
 
switch (sensors) // zatacej podle toho, kde vidis caru
{
case S: // rovne
FL; FR; // pokud se jede dlouho rovne, tak pridej
dira=0;
movement=S;
continue;
case L: // trochu vlevo
GO(L, F, FW_POMALU+rovinka); GO(R, F, FW_STREDNE+rovinka);
line=L;
dira=0;
movement=L;
continue;
case R: // trochu vpravo
GO(R, F, FW_POMALU+rovinka); GO(L, F, FW_STREDNE+rovinka);
line=R;
dira=0;
movement=R;
continue;
default: // kdyz jsou obe cidla mimo caru, tak pokracuj dal
}
rovinka=0;
if (dira>=T_DIRA) prejeddiru();
if (last!=line) // pokud si prejel caru z jedne strany na druhou stranu, tak zabrzdi
{
last=line;
speed=FW_ZATACKA;
}
if (L==line) // kdyz jsou obe cidla mimo caru, zatoc na caru
{
STOPL;
GO(R, F, speed);
movement=L;
}
else
{
STOPR;
GO(L, F, speed);
movement=R;
}
} // while(true)
}
 
/roboti/istrobot/merkur/PIC16F88/turn_R/verze/tank_funkcni.c
0,0 → 1,352
#include "tank.h"
 
#define DEBUG
 
#define TXo PIN_A3 // To the transmitter modulator
#include "AX25.c" // podprogram pro prenos telemetrie
 
unsigned int8 sensors; // pomocna promenna pro cteni cidel na caru
unsigned int8 line; // na ktere strane byla detekovana cara
unsigned int8 speed; // rychlost zataceni
unsigned int8 rovinka; // pocitadlo pro zjisteni rovneho useku
unsigned int8 last; // kde byla cara, kdyz byly minule cidla mimo
unsigned int8 movement; // obsahuje aktualni smer zataceni
unsigned int8 dira; // pocita dobu po kterou je ztracena cara
unsigned int8 cihla; // urcuje za jak dlouho muze byt znova detekovana cihla
 
// Konstanty pro dynamiku pohybu
#define T_DIRA 87 // po jakem case zataceni se detekuje dira
#define INC_SPEED 1 // prirustek rychlosti v jednom kroku
#define FW_POMALU 230 // trochu mimo caru vnitrni pas
#define FW_ZATACKA 200 // rychlost vnejsiho kola pri zataceni
#define FW_STREDNE 240 // trochu mimo caru vnejsi pas
#define COUVANI 600 // couvnuti zpet na caru, po detekci diry
#define PRES_DIRU 250
#define MAX_ROVINKA (255-FW_STREDNE)
#define TRESHOLD 10 // rozhodovaci uroven komparatoru, 0xF = 0.75*Vdd
#define BUMPER_TRESHOLD 128
#define CIK_CAK 30000
#define T_CIHLA 100 // perioda detekce cihly
 
//motory //Napred vypnout potom zapnout!
#define FR output_low(PIN_B5); output_high(PIN_B4) // Vpred
#define FL output_low(PIN_B7); output_high(PIN_B6)
#define BR output_low(PIN_B4); output_high(PIN_B5) // Vzad
#define BL output_low(PIN_B6); output_high(PIN_B7)
#define STOPR output_low(PIN_B4);output_low(PIN_B5) // Zastav
#define STOPL output_low(PIN_B6);output_low(PIN_B7)
 
#define L 0b10 // left
#define R 0b01 // right
#define S 0b11 // straight
 
//cidla
#define RSENSOR C2OUT // Senzory na caru
#define LSENSOR C1OUT
#define BUMPER PIN_A4 // Senzor na cihlu
 
#define DIAG_SERVO PIN_B3 // Propojka pro diagnosticky mod
#define DIAG_SENSORS PIN_B2 // Propojka pro diagnosticky mod
 
#DEFINE SOUND_HI PIN_A6 // komplementarni vystupy pro piezo pipak
#DEFINE SOUND_LO PIN_A7
 
char AXstring[40]; // Buffer pro prenos telemetrie
 
// makro pro PWM
#define GO(motor, direction, power) if(get_timer0()<=power) \
{direction##motor;} else {stop##motor;}
 
#int_TIMER2
void TIMER2_isr()
{
if (speed<255) speed+=INC_SPEED;
if (rovinka<MAX_ROVINKA) rovinka++;
if (dira<=T_DIRA) dira++;
if (cihla>0) cihla--;
}
// Primitivni Pipani
void beep(unsigned int16 period, unsigned int16 length)
{
unsigned int16 nn;
 
for(nn=length; nn>0; nn--)
{
output_high(SOUND_HI);output_low(SOUND_LO);
delay_us(period);
output_high(SOUND_LO);output_low(SOUND_HI);
delay_us(period);
}
}
/******************************************************************************/
void diagnostika()
{
unsigned int16 n;
 
while (input(DIAG_SERVO)) // Propojka, ktera spousti diagnostiku
{
for (n=500; n<800; n+=100)
{
beep(n,n); //beep UP
};
Delay_ms(1000);
//zastav vse
STOPL; STOPR;
//pravy pas
FR; Delay_ms(1000); STOPR; Delay_ms(1000);
BR; Delay_ms(1000); STOPR; Delay_ms(1000);
Beep(880,100); Delay_ms(1000);
//levy pas
FL; Delay_ms(1000); STOPL; Delay_ms(1000);
BL; Delay_ms(1000); STOPL; Delay_ms(1000);
Beep(880,100); Delay_ms(1000);
//oba pasy
FL; FR; Delay_ms(1000); STOPL; STOPR; Delay_ms(1000);
BL; BR; Delay_ms(1000); STOPL; STOPR; Delay_ms(1000);
};
while (input(DIAG_SENSORS))
{
int ls, rs;
while(!input(BUMPER)){beep(1100,100); Delay_ms(50);}
set_adc_channel(RSENSOR);
Delay_us(20);
rs=read_adc();
set_adc_channel(LSENSOR);
Delay_us(20);
ls=read_adc();
sprintf(AXstring,"L: %U R: %U\0", ls, rs); // Convert DATA to String.
SendPacket(&AXstring[0]);
delay_ms(1000);
};
}
///////////////////////////////////////////////////////////////////////////////
void cikcak()
{
unsigned int16 n;
sem1:
n=CIK_CAK;
while (0==RSENSOR) // zkontroluj caru
{
if (n==CIK_CAK) // zmen smer zataceni
{
n=0;
switch(movement)
{
case L:
FL;BR;
movement=R;
break;
case R:
FR;BL;
movement=L;
break;
case S:
FL;BR;
movement=R;
n=CIK_CAK/2;
break;
}
}
n++;
}
STOPL;STOPR;
line = RSENSOR; // cteni senzoru na caru
line |= LSENSOR << 1;
if (line==0) goto sem1;
// nasli jsme caru
line=S;
}
///////////////////////////////////////////////////////////////////////////////
void objizdka() // objede cihlu
{
unsigned int16 n;
 
BL;BR;Delay_ms(200);
STOPR;STOPL;
beep(900,1000);
// movement=S;
// cikcak();
 
BR; FL; Delay_ms(215); // otoc se 70° do prava
 
FR; FL; Delay_ms(600); // popojed rovne
 
BL; Delay_ms(30); // otoc se 90° do leva
STOPL; FR; Delay_ms(600);
 
FR; FL; Delay_ms(100); // popojed rovne na slepo
for(n=600;n>0;n--) // popojed rovne ale kontroluj caru
{
line = RSENSOR; // cteni senzoru na caru
line |= LSENSOR << 1;
if (line!=0) {Delay_ms(50); break;}
Delay_ms(1);
}
 
BR; // otoc se 60° do prava
for(n=600;n>0;n--)
{
line = RSENSOR; // cteni senzoru na caru
line |= LSENSOR << 1;
if (line!=0) break;
Delay_ms(1);
}
STOPR; STOPL;
 
movement=R;
cikcak();
cihla=T_CIHLA;
dira=0;
}
///////////////////////////////////////////////////////////////////////////////
void prejeddiru() // vyresi diru
{
unsigned int16 n;
unsigned int8 speed_dira;
 
STOPL;STOPR;
speed_dira=speed;
beep(1000,500);
switch (movement) //vrat se zpet na caru
{
case L:
for (n=COUVANI;n>0;n--) {GO(R,B,speed_dira); Delay_ms(1);}
STOPL;STOPR;
break;
case R:
for (n=COUVANI;n>0;n--) {GO(L,B,speed_dira); Delay_ms(1);}
STOPL;STOPR;
break;
case S:
goto sem;
break;
}
beep(800,500);
line=0;
FR; BL; Delay_ms(300); // otoc se na caru
while(line==0)
{
line = RSENSOR; // cteni senzoru na caru
line |= LSENSOR << 1;
}
FL;BR; Delay_ms(60);
STOPL; STOPR;
FL; BR; Delay_ms(500);
STOPL; STOPR;
Delay_ms(1000);
FR;FL; //popojed rovne
for(n=PRES_DIRU;n>0;n--)
{
line = RSENSOR; // cteni senzoru na caru
line |= LSENSOR << 1;
if (line!=0) break;
Delay_ms(1);
}
sem:
STOPL; STOPR;
movement=S;
cikcak(); // najdi caru
cihla=T_CIHLA;
dira=0;
}
///////////////////////////////////////////////////////////////////////////////
void main()
{
unsigned int16 n; // pro FOR
 
STOPL; STOPR; // prepne vystupy na ovladani motoru na output a zastavi
 
setup_oscillator(OSC_4MHZ|OSC_INTRC); // 4 MHz interni RC oscilator
 
port_b_pullups(TRUE); // pullups pro piano na diagnostiku
setup_spi(FALSE);
setup_timer_0(RTCC_INTERNAL|RTCC_DIV_1); // Casovac pro PWM
 
setup_timer_2(T2_DIV_BY_4,255,10); // Casovac pro regulaci
// preruseni kazdych 10ms
setup_adc_ports(sAN2|VSS_VDD); // nastaveni A/D prevodniku pro naraznik
setup_adc(ADC_CLOCK_INTERNAL);
set_adc_channel(2);
setup_timer_1(T1_INTERNAL|T1_DIV_BY_1); // Casovac pro naraznik
setup_ccp1(CCP_COMPARE_RESET_TIMER);
CCP_1=(2^10)-1; // prevod kazdou 1ms
 
setup_comparator(A0_VR_A1_VR); // inicializace komparatoru pro cidla cary
setup_vref(VREF_HIGH|TRESHOLD); // 32 kroku od 0.25 do 0.75 Vdd
 
Beep(1000,200); //double beep
Delay_ms(50);
Beep(1000,200);
Delay_ms(1000); // 1s
 
// povoleni rizeni rychlosti zataceni pres preruseni
enable_interrupts(INT_TIMER2);
enable_interrupts(GLOBAL);
 
/*---------------------------------------------------------------------------*/
sensors=S;
line=S;
last=S;
movement=S;
speed=FW_POMALU;
 
diagnostika();
// cikcak(); // toc se, abys nasel caru
Delay_ms(500);
Beep(1000,200);
Delay_ms(500);
 
while(true) // hlavni smycka (jizda podle cary)
{
sensors = RSENSOR; // cteni senzoru na caru
sensors |= LSENSOR << 1;
 
if ((read_adc(ADC_READ_ONLY)<BUMPER_TRESHOLD) && (cihla==0)) objizdka();
 
switch (sensors) // zatacej podle toho, kde vidis caru
{
case S: // rovne
FL; FR; // pokud se jede dlouho rovne, tak pridej
dira=0;
movement=S;
continue;
case L: // trochu vlevo
GO(L, F, FW_POMALU+rovinka); GO(R, F, FW_STREDNE+rovinka);
line=L;
dira=0;
movement=L;
continue;
case R: // trochu vpravo
GO(R, F, FW_POMALU+rovinka); GO(L, F, FW_STREDNE+rovinka);
line=R;
dira=0;
movement=R;
continue;
default: // kdyz jsou obe cidla mimo caru, tak pokracuj dal
}
rovinka=0;
if (dira>=T_DIRA) prejeddiru();
if (last!=line) // pokud si prejel caru z jedne strany na druhou stranu, tak zabrzdi
{
last=line;
speed=FW_ZATACKA;
}
if (L==line) // kdyz jsou obe cidla mimo caru, zatoc na caru
{
STOPL;
GO(R, F, speed);
movement=L;
}
else
{
STOPR;
GO(L, F, speed);
movement=R;
}
} // while(true)
}
 
/roboti/istrobot/merkur/PIC16F88/turn_R/verze/tank_funkcni_vecer.c
0,0 → 1,339
#include "tank.h"
 
#define DEBUG
 
#define TXo PIN_A3 // To the transmitter modulator
#include "AX25.c" // podprogram pro prenos telemetrie
 
unsigned int8 sensors; // pomocna promenna pro cteni cidel na caru
unsigned int8 line; // na ktere strane byla detekovana cara
unsigned int8 speed; // rychlost zataceni
unsigned int8 rovinka; // pocitadlo pro zjisteni rovneho useku
unsigned int8 last; // kde byla cara, kdyz byly minule cidla mimo
unsigned int8 movement; // obsahuje aktualni smer zataceni
unsigned int8 dira; // pocita dobu po kterou je ztracena cara
 
// Konstanty pro dynamiku pohybu
#define T_DIRA 120 // po jakem case zataceni se detekuje dira
#define INC_SPEED 1 // prirustek rychlosti v jednom kroku
#define FW_POMALU 230 // trochu mimo caru vnitrni pas
#define FW_ZATACKA 240 // rychlost vnejsiho kola pri zataceni
#define FW_STREDNE 240 // trochu mimo caru vnejsi pas
#define COUVANI 750 // couvnuti zpet na caru, po detekci diry
#define PRES_DIRU 300
#define MAX_ROVINKA (255-FW_STREDNE)
#define TRESHOLD 6 // rozhodovaci uroven komparatoru, 0xF = 0.75*Vdd
#define BUMPER_TRESHOLD 128
#define CIK_CAK 30000
#define T_CIHLA 50 // perioda detekce cihly
 
//motory //Napred vypnout potom zapnout!
#define FR output_low(PIN_B5); output_high(PIN_B4) // Vpred
#define FL output_low(PIN_B7); output_high(PIN_B6)
#define BR output_low(PIN_B4); output_high(PIN_B5) // Vzad
#define BL output_low(PIN_B6); output_high(PIN_B7)
#define STOPR output_low(PIN_B4);output_low(PIN_B5) // Zastav
#define STOPL output_low(PIN_B6);output_low(PIN_B7)
 
#define L 0b10 // left
#define R 0b01 // right
#define S 0b11 // straight
 
//cidla
#define RSENSOR C2OUT // Senzory na caru
#define LSENSOR C1OUT
#define BUMPER PIN_A4 // Senzor na cihlu
 
#define DIAG_SERVO PIN_B3 // Propojka pro diagnosticky mod
#define DIAG_SENSORS PIN_B2 // Propojka pro diagnosticky mod
 
#DEFINE SOUND_HI PIN_A6 // komplementarni vystupy pro piezo pipak
#DEFINE SOUND_LO PIN_A7
 
char AXstring[40]; // Buffer pro prenos telemetrie
 
// makro pro PWM
#define GO(motor, direction, power) if(get_timer0()<=power) \
{direction##motor;} else {stop##motor;}
 
#int_TIMER2
void TIMER2_isr()
{
if (speed<255) speed+=INC_SPEED;
if (rovinka<MAX_ROVINKA) rovinka++;
if (dira<=T_DIRA) dira++;
}
// Primitivni Pipani
void beep(unsigned int16 period, unsigned int16 length)
{
unsigned int16 nn;
 
for(nn=length; nn>0; nn--)
{
output_high(SOUND_HI);output_low(SOUND_LO);
delay_us(period);
output_high(SOUND_LO);output_low(SOUND_HI);
delay_us(period);
}
}
/******************************************************************************/
void diagnostika()
{
unsigned int16 n;
 
while (input(DIAG_SERVO)) // Propojka, ktera spousti diagnostiku
{
for (n=500; n<800; n+=100)
{
beep(n,n); //beep UP
};
Delay_ms(1000);
//zastav vse
STOPL; STOPR;
//pravy pas
FR; Delay_ms(1000); STOPR; Delay_ms(1000);
BR; Delay_ms(1000); STOPR; Delay_ms(1000);
Beep(880,100); Delay_ms(1000);
//levy pas
FL; Delay_ms(1000); STOPL; Delay_ms(1000);
BL; Delay_ms(1000); STOPL; Delay_ms(1000);
Beep(880,100); Delay_ms(1000);
//oba pasy
FL; FR; Delay_ms(1000); STOPL; STOPR; Delay_ms(1000);
BL; BR; Delay_ms(1000); STOPL; STOPR; Delay_ms(1000);
};
while (input(DIAG_SENSORS)) // spusteni diagnostiky cidel
{
if (RSENSOR) beep(900,500);
if (LSENSOR) beep(800,500);
if ((read_adc(ADC_READ_ONLY)<BUMPER_TRESHOLD)) beep(1000,500);
};
}
///////////////////////////////////////////////////////////////////////////////
void cikcak()
{
unsigned int16 n;
sem1:
n=CIK_CAK;
while (0==RSENSOR||LSENSOR) // zkontroluj caru
{
if (n==CIK_CAK) // zmen smer zataceni
{
n=0;
switch(movement)
{
case L:
FL;BR;
movement=R;
break;
case R:
FR;BL;
movement=L;
break;
case S:
FL;BR;
movement=R;
n=CIK_CAK/2;
break;
}
}
n++;
}
STOPL;STOPR;
line = RSENSOR; // cteni senzoru na caru
line |= LSENSOR << 1;
if (line==0) goto sem1;
// nasli jsme caru
line=S;
}
///////////////////////////////////////////////////////////////////////////////
void objizdka() // objede cihlu
{
unsigned int16 n;
 
BL;BR;Delay_ms(150);
STOPR;STOPL;
beep(900,1000);
// movement=S;
// cikcak();
 
BR; FL; Delay_ms(225); // otoc se 70° do prava
 
FR; FL; Delay_ms(700); // popojed rovne
 
BL; Delay_ms(30); // otoc se 90° do leva
STOPL; FR; Delay_ms(500);
 
FR; FL; Delay_ms(150); // popojed rovne na slepo
for(n=600;n>0;n--) // popojed rovne ale kontroluj caru
{
line = RSENSOR; // cteni senzoru na caru
line |= LSENSOR << 1;
if (line!=0) {Delay_ms(50); break;}
Delay_ms(1);
}
 
BR; // otoc se 60° do prava
for(n=600;n>0;n--)
{
line = RSENSOR; // cteni senzoru na caru
line |= LSENSOR << 1;
if (line!=0) break;
Delay_ms(1);
}
STOPR; STOPL;
 
movement=R;
cikcak();
dira=0;
}
///////////////////////////////////////////////////////////////////////////////
void prejeddiru() // vyresi diru
{
unsigned int16 n;
unsigned int8 speed_dira;
 
STOPL;STOPR;
speed_dira=speed;
beep(1000,500);
switch (movement) //vrat se zpet na caru
{
case L:
for (n=COUVANI;n>0;n--) {GO(R,B,speed_dira); Delay_ms(1);}
STOPL;STOPR;
break;
case R:
for (n=COUVANI;n>0;n--) {GO(L,B,speed_dira); Delay_ms(1);}
STOPL;STOPR;
break;
case S:
goto sem;
break;
}
beep(1000,500);
 
line=0;
FR; BL; Delay_ms(400); // otoc se na caru
beep(1000,500);
while(line==0)
{
line = RSENSOR; // cteni senzoru na caru
line |= LSENSOR << 1;
}
FL;BR; Delay_ms(60); // zabrzdi
STOPL; STOPR;
FL; BR; Delay_ms(700); // otacka 180 deg
STOPL; STOPR;
 
FR;FL; //popojed rovne
for(n=PRES_DIRU;n>0;n--)
{
line = RSENSOR; // cteni senzoru na caru
line |= LSENSOR << 1;
if (line!=0) break;
Delay_ms(1);
}
sem:
STOPL; STOPR;
movement=S;
cikcak(); // najdi caru
dira=0;
}
///////////////////////////////////////////////////////////////////////////////
void main()
{
unsigned int16 n; // pro FOR
 
STOPL; STOPR; // prepne vystupy na ovladani motoru na output a zastavi
 
setup_oscillator(OSC_4MHZ|OSC_INTRC); // 4 MHz interni RC oscilator
 
port_b_pullups(TRUE); // pullups pro piano na diagnostiku
setup_spi(FALSE);
setup_timer_0(RTCC_INTERNAL|RTCC_DIV_1); // Casovac pro PWM
 
setup_timer_2(T2_DIV_BY_4,255,10); // Casovac pro regulaci
// preruseni kazdych 10ms
setup_adc_ports(sAN2|VSS_VDD); // nastaveni A/D prevodniku pro naraznik
setup_adc(ADC_CLOCK_INTERNAL);
set_adc_channel(2);
setup_timer_1(T1_INTERNAL|T1_DIV_BY_1); // Casovac pro naraznik
setup_ccp1(CCP_COMPARE_RESET_TIMER);
CCP_1=(2^10)-1; // prevod kazdou 1ms
 
setup_comparator(A0_VR_A1_VR); // inicializace komparatoru pro cidla cary
setup_vref(VREF_HIGH|TRESHOLD); // 32 kroku od 0.25 do 0.75 Vdd
 
Beep(1000,200); //double beep
Delay_ms(50);
Beep(1000,200);
Delay_ms(1000); // 1s
 
// povoleni rizeni rychlosti zataceni pres preruseni
enable_interrupts(INT_TIMER2);
enable_interrupts(GLOBAL);
 
/*---------------------------------------------------------------------------*/
sensors=S;
line=S;
last=S;
movement=S;
speed=FW_POMALU;
 
diagnostika();
//cikcak(); // toc se, abys nasel caru
Delay_ms(500);
Beep(1000,200);
Delay_ms(500);
 
while(true) // hlavni smycka (jizda podle cary)
{
sensors = RSENSOR; // cteni senzoru na caru
sensors |= LSENSOR << 1;
 
if ((read_adc(ADC_READ_ONLY)<BUMPER_TRESHOLD) && (dira<=T_CIHLA)) objizdka();
 
switch (sensors) // zatacej podle toho, kde vidis caru
{
case S: // rovne
FL; FR; // pokud se jede dlouho rovne, tak pridej
dira=0;
movement=S;
continue;
case L: // trochu vlevo
GO(L, F, FW_POMALU+rovinka); GO(R, F, FW_STREDNE+rovinka);
line=L;
dira=0;
movement=L;
continue;
case R: // trochu vpravo
GO(R, F, FW_POMALU+rovinka); GO(L, F, FW_STREDNE+rovinka);
line=R;
dira=0;
movement=R;
continue;
default: // kdyz jsou obe cidla mimo caru, tak pokracuj dal
}
rovinka=0;
if (dira>=T_DIRA) prejeddiru();
if (last!=line) // pokud si prejel caru z jedne strany na druhou stranu, tak zabrzdi
{
last=line;
speed=FW_ZATACKA;
}
if (L==line) // kdyz jsou obe cidla mimo caru, zatoc na caru
{
STOPL;
GO(R, F, speed);
movement=L;
}
else
{
STOPR;
GO(L, F, speed);
movement=R;
}
} // while(true)
}
 
/roboti/istrobot/merkur/PIC16F88/vystava/AX25.c
0,0 → 1,135
#nolist
//#define PTT PIN_A2 // PTT control
//#define TXo PIN_C0 // To the transmitter modulator
#define PERIODAH delay_us(222) // Halfperiod H 222;78/1200 500;430/500
#define TAILH delay_us(78)
#define PERIODAL delay_us(412) // Halfperiod L 412;345/1200 1000;880/500
#define TAILL delay_us(345)
#byte STATUS = 3 // CPUs status register
 
byte SendData[16] = {'A'<<1, 'L'<<1, 'L'<<1, ' '<<1, ' '<<1, ' '<<1, 0x60,
'C'<<1, 'Z'<<1, '0'<<1, 'R'<<1, 'R'<<1, 'R'<<1, 0x61,
0x03, 0xF0};
 
boolean bit;
int fcslo, fcshi; // variabloes for calculating FCS (CRC)
int stuff; // stuff counter for extra 0
int flag_flag; // if it is sending flag (7E)
int fcs_flag; // if it is sending Frame Check Sequence
int i; // for for
 
void flipout() //flips the state of output pin a_1
{
stuff = 0; //since this is a 0, reset the stuff counter
if (bit)
{
bit=FALSE; //if the state of the pin was low, make it high.
}
else
{
bit=TRUE; //if the state of the pin was high make it low
}
}
 
void fcsbit(byte tbyte)
{
#asm
BCF STATUS,0
RRF fcshi,F // rotates the entire 16 bits
RRF fcslo,F // to the right
#endasm
if (((STATUS & 0x01)^(tbyte)) ==0x01)
{
fcshi = fcshi^0x84;
fcslo = fcslo^0x08;
}
}
 
void SendBit ()
{
if (bit)
{
output_high(TXo);
PERIODAH;
output_low(TXo);
PERIODAH;
output_high(TXo);
PERIODAH;
output_low(TXo);
TAILH;
}
else
{
output_high(TXo);
PERIODAL;
output_low(TXo);
TAILL;
};
}
 
void SendByte (byte inbyte)
{
int k, bt;
 
for (k=0;k<8;k++) //do the following for each of the 8 bits in the byte
{
bt = inbyte & 0x01; //strip off the rightmost bit of the byte to be sent (inbyte)
if ((fcs_flag == FALSE) & (flag_flag == FALSE)) fcsbit(bt); //do FCS calc, but only if this
//is not a flag or fcs byte
if (bt == 0)
{
flipout();
} // if this bit is a zero, flip the output state
else
{ //otherwise if it is a 1, do the following:
if (flag_flag == FALSE) stuff++; //increment the count of consequtive 1's
if ((flag_flag == FALSE) & (stuff == 5))
{ //stuff an extra 0, if 5 1's in a row
SendBit();
flipout(); //flip the output state to stuff a 0
}//end of if
}//end of else
// delay_us(850); //introduces a delay that creates 1200 baud
SendBit();
inbyte = inbyte>>1; //go to the next bit in the byte
}//end of for
}//end of SendByte
 
void SendPacket(char *data)
{
bit=FALSE;
 
fcslo=fcshi=0xFF; //The 2 FCS Bytes are initialized to FF
stuff = 0; //The variable stuff counts the number of 1's in a row. When it gets to 5
// it is time to stuff a 0.
 
// output_low(PTT); // Blinking LED
// delay_ms(1000);
// output_high(PTT);
 
flag_flag = TRUE; //The variable flag is true if you are transmitted flags (7E's) false otherwise.
fcs_flag = FALSE; //The variable fcsflag is true if you are transmitting FCS bytes, false otherwise.
 
for(i=0; i<10; i++) SendByte(0x7E); //Sends flag bytes. Adjust length for txdelay
//each flag takes approx 6.7 ms
flag_flag = FALSE; //done sending flags
 
for(i=0; i<16; i++) SendByte(SendData[i]); //send the packet bytes
 
for(i=0; 0 != *data; i++)
{
SendByte(*data); //send the packet bytes
data++;
};
 
fcs_flag = TRUE; //about to send the FCS bytes
fcslo =fcslo^0xff; //must XOR them with FF before sending
fcshi = fcshi^0xff;
SendByte(fcslo); //send the low byte of fcs
SendByte(fcshi); //send the high byte of fcs
fcs_flag = FALSE; //done sending FCS
flag_flag = TRUE; //about to send flags
SendByte(0x7e); // Send a flag to end packet
}
 
#list
/roboti/istrobot/merkur/PIC16F88/vystava/tank.BAK
0,0 → 1,236
#include "tank.h"
 
unsigned int8 sensors; // pomocna promenna pro cteni cidel na caru
unsigned int8 line; // na ktere strane byla detekovana cara
unsigned int8 speed; // rychlost zataceni
unsigned int8 last; // kde byla cara, kdyz byly minule cidla mimo
unsigned int8 rovinka; // pocitadlo pro zjisteni rovneho useku
int cirkus;
 
// Konstanty pro dynamiku pohybu
#define T_DIRA 120 // po jakem case zataceni se detekuje dira
#define FW_POMALU 170 // trochu mimo caru vnitrni pas
#define FW_ZATACKA 200 // rychlost vnejsiho kola pri zataceni
#define FW_STREDNE 190 // trochu mimo caru vnejsi pas
#define COUVANI 750 // couvnuti zpet na caru, po detekci diry
#define MAX_ROVINKA (255-FW_STREDNE)
#define TRESHOLD 15 // rozhodovaci uroven komparatoru, 0xF = 0.75*Vdd
#define BUMPER_TRESHOLD 128
 
//motory //Napred vypnout potom zapnout!
#define FR output_low(PIN_B5); output_high(PIN_B4) // Vpred
#define FL output_low(PIN_B7); output_high(PIN_B6)
#define BR output_low(PIN_B4); output_high(PIN_B5) // Vzad
#define BL output_low(PIN_B6); output_high(PIN_B7)
#define STOPR output_low(PIN_B4);output_low(PIN_B5) // Zastav
#define STOPL output_low(PIN_B6);output_low(PIN_B7)
 
#define L 0b10 // left
#define R 0b01 // right
#define S 0b11 // straight
 
//cidla
#define RSENSOR !C2OUT // Senzory na caru
#define LSENSOR !C1OUT
#define BUMPER PIN_A4 // Senzor na cihlu
 
#define DIAG_SERVO PIN_B3 // Propojka pro diagnosticky mod
#define DIAG_SENSORS PIN_B2 // Propojka pro diagnosticky mod
 
#DEFINE SOUND_HI PIN_A6 // komplementarni vystupy pro piezo pipak
#DEFINE SOUND_LO PIN_A7
 
char AXstring[40]; // Buffer pro prenos telemetrie
 
// makro pro PWM
#define GO(motor, direction, power) if(get_timer0()<=power) \
{direction##motor;} else {stop##motor;}
 
#int_TIMER2
void TIMER2_isr()
{
if (speed<255) speed++;
if (rovinka<MAX_ROVINKA) rovinka++;
}
// Primitivni Pipani
void beep(unsigned int16 period, unsigned int16 length)
{
unsigned int16 nn;
 
for(nn=length; nn>0; nn--)
{
output_high(SOUND_HI);output_low(SOUND_LO);
delay_us(period);
output_high(SOUND_LO);output_low(SOUND_HI);
delay_us(period);
}
}
/******************************************************************************/
void diagnostika()
{
unsigned int16 n;
 
while (input(DIAG_SERVO)) // Propojka, ktera spousti diagnostiku
{
for (n=500; n<800; n+=100)
{
beep(n,n); //beep UP
};
Delay_ms(1000);
//zastav vse
STOPL; STOPR;
//pravy pas
FR; Delay_ms(1000); STOPR; Delay_ms(1000);
BR; Delay_ms(1000); STOPR; Delay_ms(1000);
Beep(880,100); Delay_ms(1000);
//levy pas
FL; Delay_ms(1000); STOPL; Delay_ms(1000);
BL; Delay_ms(1000); STOPL; Delay_ms(1000);
Beep(880,100); Delay_ms(1000);
//oba pasy
FL; FR; Delay_ms(1000); STOPL; STOPR; Delay_ms(1000);
BL; BR; Delay_ms(1000); STOPL; STOPR; Delay_ms(1000);
};
while (input(DIAG_SENSORS)) // spusteni diagnostiky cidel
{
if (RSENSOR) beep(1000,1000);
if (LSENSOR) beep(2000,2000);
if ((read_adc(ADC_READ_ONLY)<BUMPER_TRESHOLD)) beep(3000,3000);
};
}
///////////////////////////////////////////////////////////////////////////////
void OtocSe() // otoci se zpet, kdyz je prekazka
{
unsigned int16 n;
 
STOPR;STOPL;
beep(800,400);
beep(2000,1000);
beep(900,400);
 
BR; FL; Delay_ms(100); // otoc se 30° do prava
STOPL; STOPR;
beep(1000,1000);
 
BR; FL;
for(n=40000;n>0;n--) // toc se, dokud nenarazis na caru
{
line = RSENSOR; // cteni senzoru na caru
line |= LSENSOR << 1;
if (line!=0) break;
}
STOPR; STOPL;
 
line=L; // caru jsme prejeli, tak je vlevo
cirkus=0;
}
 
 
void main()
{
unsigned int16 n; // pro FOR
unsigned int16 i;
 
STOPL; STOPR; // prepne vystupy na ovladani motoru na output a zastavi
 
setup_oscillator(OSC_4MHZ|OSC_INTRC); // 4 MHz interni RC oscilator
 
port_b_pullups(TRUE); // pullups pro piano na diagnostiku
setup_spi(FALSE);
setup_timer_0(RTCC_INTERNAL|RTCC_DIV_1); // Casovac pro PWM
 
setup_timer_2(T2_DIV_BY_4,255,10); // Casovac pro regulaci
// preruseni kazdych 10ms
setup_adc_ports(sAN2|VSS_VDD); // nastaveni A/D prevodniku pro naraznik
setup_adc(ADC_CLOCK_INTERNAL);
set_adc_channel(2);
setup_timer_1(T1_INTERNAL|T1_DIV_BY_1); // Casovac pro naraznik
setup_ccp1(CCP_COMPARE_RESET_TIMER);
CCP_1=(2^10)-1; // prevod kazdou 1ms
 
setup_comparator(A0_VR_A1_VR); // inicializace komparatoru pro cidla cary
setup_vref(VREF_HIGH|TRESHOLD); // 32 kroku od 0.25 do 0.75 Vdd
 
Beep(1000,200); //double beep
Delay_ms(50);
Beep(1000,200);
Delay_ms(1000); // 1s
 
// povoleni rizeni rychlosti zataceni pres preruseni
enable_interrupts(INT_TIMER2);
enable_interrupts(GLOBAL);
 
/*---------------------------------------------------------------------------*/
sensors=S;
line=S;
last=S;
cirkus=0;
// movement=S;
speed=FW_POMALU;
 
diagnostika();
Delay_ms(500);
Beep(1000,200);
Delay_ms(500);
 
while(true) // hlavni smycka (jizda podle cary)
{
sensors = RSENSOR; // cteni senzoru na caru
sensors |= LSENSOR << 1;
 
if (read_adc(ADC_READ_ONLY)<BUMPER_TRESHOLD) OtocSe();
 
switch (sensors) // zatacej podle toho, kde vidis caru
{
case S: // rovne
GO(L, F, FW_STREDNE+rovinka); GO(R, F, FW_STREDNE+rovinka);
continue;
case L: // trochu vlevo
GO(L, F, FW_POMALU+rovinka); GO(R, F, FW_STREDNE+rovinka);
line=L;
continue;
case R: // trochu vpravo
GO(R, F, FW_POMALU+rovinka); GO(L, F, FW_STREDNE+rovinka);
line=R;
continue;
default: // kdyz jsou obe cidla mimo caru, tak pokracuj dal
};
rovinka=0;
 
if (last!=line) // pokud si prejel caru z jedne strany na druhou stranu, tak zabrzdi
{
last=line;
speed=FW_ZATACKA;
cirkus++;
if (cirkus>10)
{
STOPL; STOPR;
cirkus=0;
disable_interrupts(GLOBAL);
beep(1000,400);
for(n=3000; n>3950; n--) beep(n,10);
beep(2000,200);
beep(900,400);
for(n=2950; n<3000; n++) beep(n,10);
beep(4000,400);
beep(1000,100);
beep(3000,400);
Delay_ms(1000);
enable_interrupts(GLOBAL);
}
};
 
if (L==line) // kdyz jsou obe cidla mimo caru, zatoc na caru
{
STOPL;
GO(R, F, speed);
}
else
{
STOPR;
GO(L, F, speed);
}
 
} // while(true)
}
 
/roboti/istrobot/merkur/PIC16F88/vystava/tank.HEX
0,0 → 1,157
:1000000000308A008E2A0000FF00030E8301A10049
:100010007F08A0000A08A8008A01A00E0408A20018
:100020007708A3007808A4007908A5007A08A6003C
:100030007B08A700831383128C308400801C222845
:100040008C183528220884002308F7002408F800BB
:100050002508F9002608FA002708FB0028088A006E
:10006000210E8300FF0E7F0E09008A1137282B0F07
:100070003A283B28AB0A2D08403C0318AD0A8C10E7
:100080008A1122281230E302031C542863308400B2
:10009000FC3080050310800C800C000803195428E4
:1000A00052280000800B512800346008E2005F08ED
:1000B000E100E108031D5F28E20803197A2883168E
:1000C00005138312051783168513831285135D08A4
:1000D000E3004220831685138312851783160513C8
:1000E000831205135D08E300422061080319E2034F
:1000F000E103592800345E308400000803198F287A
:100100000130F800F701F70B8328F80B82284A30FA
:10011000F700F70B892800000000800B80280034CE
:10012000831686158312861DBB290130DC00F4304E
:10013000DB005C08033C031CB128031DA3285B08FB
:100140001F3C031CB1285C08DE005B08DD005C0876
:10015000E0005B08DF0055206430DB070318DC0A91
:1001600099280430DD00FA30DE007B20DD0BB32857
:1001700083160613831206138316861383128613BF
:1001800083160612831206128316861283128612B3
:10019000831686128312861283160612831206169F
:1001A0000430DD00FA30DE007B20DD0BD228831620
:1001B00006128312061283168612831286120430E8
:1001C000DD00FA30DE007B20DD0BE128831606120D
:1001D0008312061283168612831286160430DD00FF
:1001E000FA30DE007B20DD0BF02883160612831226
:1001F000061283168612831286120430DD00FA304E
:10020000DE007B20DD0BFF280330DE007030DD00D8
:10021000E0016430DF0055200430DD00FA30DE00FC
:100220007B20DD0B0E29831686138312861383161B
:100230000613831206170430DD00FA30DE007B203F
:10024000DD0B1D29831606138312061383168613EE
:10025000831286130430DD00FA30DE007B20DD0BD4
:100260002C29831606138312061383168613831212
:1002700086170430DD00FA30DE007B20DD0B3B29E1
:1002800083160613831206138316861383128613AE
:100290000430DD00FA30DE007B20DD0B4A2903301C
:1002A000DE007030DD00E0016430DF0055200430F6
:1002B000DD00FA30DE007B20DD0B59298316861322
:1002C000831286138316061383120617831686126B
:1002D0008312861283160612831206160430DD007E
:1002E000FA30DE007B20DD0B7029831606138312A3
:1002F000061383168613831286138316061283123F
:10030000061283168612831286120430DD00FA303C
:10031000DE007B20DD0B872983160613831206136C
:10032000831686138312861783160612831206120B
:1003300083168612831286160430DD00FA30DE0042
:100340007B20DD0B9E29831606138312061383166A
:1003500086138312861383160612831206128316DF
:100360008612831286120430DD00FA30DE007B2014
:10037000DD0BB5299028831606158312061DEE297C
:1003800083169C1BCE2903308312DE00E830DD008B
:100390000330E000E830DF00552083161C1BDB290A
:1003A00007308312DE00D030DD000730E000D030AF
:1003B000DF005520831683121F1DE0298316DB29D9
:1003C0001E087F3C031CED290B30DE00B830DD0039
:1003D0000B30E000B830DF005520BB298A111F2BFD
:1003E000831606128312061283168612831286164D
:1003F0008316061383120613831686138312861739
:100400000330DE002030DD000130E0009030DF00FE
:1004100055200730DE00D030DD000330E000E8304A
:10042000DF0055200330DE008430DD000130E000C5
:100430009030DF00552083160612831206128316B1
:1004400086128312861683168613831286138316EA
:100450000613831206173230DE007B208316061344
:1004600083120613831686138312861383160612CD
:100470008312061283168612831286120330DE0060
:10048000E830DD000330E000E830DF00552083165F
:10049000061283120612831686128312861683169C
:1004A00086138312861383160613831206179C3055
:1004B000DC004030DB00DB08031D612ADC08031987
:1004C000792AAA0183169C1B682A8312AA0A83161A
:1004D00000301C1F0130F7000310F70D770883125E
:1004E000AA04AA08031D792A5B080319DC03DB03AD
:1004F0005B2A831606128312061283168612831253
:10050000861283160613831206138316861383122C
:1005100086130230AA00AE018A114B2B84011F30D2
:10052000830583161F129F121B0880399B0007301A
:100530009C001C0883120D13603083168F00061375
:1005400083120613831686138312861383160612EC
:100550008312061283168612831286126230831665
:100560008F008113831294128316061186140612CB
:10057000003083129400831694000108C7390838AC
:1005800081004830F800053883129200FF3083164E
:1005900092001F129F121B08803904389B001F1302
:1005A00083121F179F1783169F1383121F14103077
:1005B000F8001F08C73978049F0085309000831623
:1005C00086150B3083129700960107309500023094
:1005D00083169C000508033885000330F700F70BED
:1005E000EF2A1C0883120D138F3083169D000330F1
:1005F0008312DE00E830DD00E001C830DF00552066
:100600003230DE007B200330DE00E830DD00E00128
:10061000C830DF0055200430DB00FA30DE007B20DC
:10062000DB0B0D2B83168C14C03083128B0403302C
:10063000A900AA00AC00AE01AA30AB00902802309D
:10064000DB00FA30DE007B20DB0B212B0330DE00E9
:10065000E830DD00E001C830DF0055200230DB006B
:10066000FA30DE007B20DB0B302BA90183169C1BAC
:100670003C2B8312A90A831600301C1F0130F7009F
:100680000310F70D77088312A9041F19452B1E08C4
:100690007F3C0318F0292908033A0319562B013A25
:1006A00003198B2B033A0319C22BF92B0108DB002A
:1006B000BE302D075B0203195F2B0318682B8316CE
:1006C0008613831286138316061383120617702B64
:1006D000831606138312061383168613831286135A
:1006E0000108DB00BE302D075B020319792B0318CC
:1006F000822B8316861283128612831606128312A9
:1007000006168A2B83160612831206128316861289
:1007100083128612352B0108DB00AA302D075B02FD
:100720000319942B03189D2B8316861383128613AB
:100730008316061383120617A52B8316061383123E
:10074000061383168613831286130108DB00BE305E
:100750002D075B020319AE2B0318B72B83168612E5
:10076000831286128316061283120616BF2B831677
:100770000612831206128316861283128612023024
:10078000AA00352B0108DB00AA302D075B020319F4
:10079000CB2B0318D42B8316861283128612831652
:1007A000061283120616DC2B83160612831206121B
:1007B00083168612831286120108DB00BE302D07D5
:1007C0005B020319E52B0318EE2B831686138312A5
:1007D00086138316061383120617F62B8316061349
:1007E0008312061383168613831286130130AA0020
:1007F000352BAD012A082C0203198F2C2A08AC00D6
:10080000C830AB00AE0A2E080A3C03188F2C8316A2
:100810000613831206138316861383128613831618
:100820000612831206128316861283128612AE01F6
:100830000B138B138B1B192C0330DE00E830DD000B
:100840000130E0009030DF0055200B30D800B83088
:10085000D70058080E3C0318412CFF3A031D342CD6
:1008600057086E3C0318412C5808DE005708DD007D
:10087000E0010A30DF00552057080319D803D703D9
:10088000292C0730DE00D030DD00E001C830DF0069
:1008900055200330DE008430DD000130E000903070
:1008A000DF0055200B30D8008630D70058080B3CAD
:1008B000031C6C2C031D602C5708B73C031C6C2CCC
:1008C0005808DE005708DD00E0010A30DF0055203F
:1008D000D70A0319D80A562C0F30DE00A030DD00ED
:1008E0000130E0009030DF0055200330DE00E830BA
:1008F000DD00E0016430DF0055200B30DE00B83051
:10090000DD000130E0009030DF0055200430DB00D6
:10091000FA30DE007B20DB0B882CC0308B042A08E9
:10092000023C031DB12C8316061383120613831693
:1009300086138312861301082B02031CA82C83162E
:100940008612831286128316061283120616B02CA4
:1009500083160612831206128316861283128612DB
:10096000CE2C831606128312061283168612831269
:10097000861201082B02031CC62C831686138312D1
:1009800086138316061383120617CE2C83160613BE
:10099000831206138316861383128613352B630086
:04400E00383FFC3FFC
:00000001FF
;PIC16F88
/roboti/istrobot/merkur/PIC16F88/vystava/tank.LST
0,0 → 1,1497
CCS PCM C Compiler, Version 3.221, 27853 20-V-05 13:52
 
Filename: D:\KAKLIK\programy\PIC_C\roboti\merkur\PIC16F88\vystava\tank.LST
 
ROM used: 1232 words (30%)
Largest free fragment is 2048
RAM used: 65 (37%) at main() level
73 (42%) worst case
Stack: 4 worst case (3 in main + 1 for interrupts)
 
*
0000: MOVLW 00
0001: MOVWF 0A
0002: GOTO 28E
0003: NOP
0004: MOVWF 7F
0005: SWAPF 03,W
0006: CLRF 03
0007: MOVWF 21
0008: MOVF 7F,W
0009: MOVWF 20
000A: MOVF 0A,W
000B: MOVWF 28
000C: CLRF 0A
000D: SWAPF 20,F
000E: MOVF 04,W
000F: MOVWF 22
0010: MOVF 77,W
0011: MOVWF 23
0012: MOVF 78,W
0013: MOVWF 24
0014: MOVF 79,W
0015: MOVWF 25
0016: MOVF 7A,W
0017: MOVWF 26
0018: MOVF 7B,W
0019: MOVWF 27
001A: BCF 03.7
001B: BCF 03.5
001C: MOVLW 8C
001D: MOVWF 04
001E: BTFSS 00.1
001F: GOTO 022
0020: BTFSC 0C.1
0021: GOTO 035
0022: MOVF 22,W
0023: MOVWF 04
0024: MOVF 23,W
0025: MOVWF 77
0026: MOVF 24,W
0027: MOVWF 78
0028: MOVF 25,W
0029: MOVWF 79
002A: MOVF 26,W
002B: MOVWF 7A
002C: MOVF 27,W
002D: MOVWF 7B
002E: MOVF 28,W
002F: MOVWF 0A
0030: SWAPF 21,W
0031: MOVWF 03
0032: SWAPF 7F,F
0033: SWAPF 7F,W
0034: RETFIE
0035: BCF 0A.3
0036: GOTO 037
.................... #include "tank.h"
.................... #include <16F88.h>
.................... //////// Standard Header file for the PIC16F88 device ////////////////
.................... #device PIC16F88
.................... #list
....................
.................... #device adc=8
.................... #fuses NOWDT,INTRC_IO, NOPUT, MCLR, NOBROWNOUT, NOLVP, NOCPD, NOWRT, NODEBUG, NOPROTECT, NOFCMEN, NOIESO
.................... #use delay(clock=4000000)
*
0042: MOVLW 12
0043: SUBWF 63,F
0044: BTFSS 03.0
0045: GOTO 054
0046: MOVLW 63
0047: MOVWF 04
0048: MOVLW FC
0049: ANDWF 00,F
004A: BCF 03.0
004B: RRF 00,F
004C: RRF 00,F
004D: MOVF 00,W
004E: BTFSC 03.2
004F: GOTO 054
0050: GOTO 052
0051: NOP
0052: DECFSZ 00,F
0053: GOTO 051
0054: RETLW 00
*
007B: MOVLW 5E
007C: MOVWF 04
007D: MOVF 00,W
007E: BTFSC 03.2
007F: GOTO 08F
0080: MOVLW 01
0081: MOVWF 78
0082: CLRF 77
0083: DECFSZ 77,F
0084: GOTO 083
0085: DECFSZ 78,F
0086: GOTO 082
0087: MOVLW 4A
0088: MOVWF 77
0089: DECFSZ 77,F
008A: GOTO 089
008B: NOP
008C: NOP
008D: DECFSZ 00,F
008E: GOTO 080
008F: RETLW 00
....................
....................
....................
.................... unsigned int8 sensors; // pomocna promenna pro cteni cidel na caru
.................... unsigned int8 line; // na ktere strane byla detekovana cara
.................... unsigned int8 speed; // rychlost zataceni
.................... unsigned int8 last; // kde byla cara, kdyz byly minule cidla mimo
.................... unsigned int8 rovinka; // pocitadlo pro zjisteni rovneho useku
.................... int cirkus;
....................
.................... // Konstanty pro dynamiku pohybu
.................... #define T_DIRA 120 // po jakem case zataceni se detekuje dira
.................... #define FW_POMALU 170 // trochu mimo caru vnitrni pas
.................... #define FW_ZATACKA 200 // rychlost vnejsiho kola pri zataceni
.................... #define FW_STREDNE 190 // trochu mimo caru vnejsi pas
.................... #define COUVANI 750 // couvnuti zpet na caru, po detekci diry
.................... #define MAX_ROVINKA (255-FW_STREDNE)
.................... #define TRESHOLD 15 // rozhodovaci uroven komparatoru, 0xF = 0.75*Vdd
.................... #define BUMPER_TRESHOLD 128
....................
.................... //motory //Napred vypnout potom zapnout!
.................... #define FR output_low(PIN_B5); output_high(PIN_B4) // Vpred
.................... #define FL output_low(PIN_B7); output_high(PIN_B6)
.................... #define BR output_low(PIN_B4); output_high(PIN_B5) // Vzad
.................... #define BL output_low(PIN_B6); output_high(PIN_B7)
.................... #define STOPR output_low(PIN_B4);output_low(PIN_B5) // Zastav
.................... #define STOPL output_low(PIN_B6);output_low(PIN_B7)
....................
.................... #define L 0b10 // left
.................... #define R 0b01 // right
.................... #define S 0b11 // straight
....................
.................... //cidla
.................... #define RSENSOR !C2OUT // Senzory na caru
.................... #define LSENSOR !C1OUT
.................... #define BUMPER PIN_A4 // Senzor na cihlu
....................
.................... #define DIAG_SERVO PIN_B3 // Propojka pro diagnosticky mod
.................... #define DIAG_SENSORS PIN_B2 // Propojka pro diagnosticky mod
....................
.................... #DEFINE SOUND_HI PIN_A6 // komplementarni vystupy pro piezo pipak
.................... #DEFINE SOUND_LO PIN_A7
....................
.................... char AXstring[40]; // Buffer pro prenos telemetrie
....................
.................... // makro pro PWM
.................... #define GO(motor, direction, power) if(get_timer0()<=power) \
.................... {direction##motor;} else {stop##motor;}
....................
.................... #int_TIMER2
.................... void TIMER2_isr()
.................... {
.................... if (speed<255) speed++;
*
0037: INCFSZ 2B,W
0038: GOTO 03A
0039: GOTO 03B
003A: INCF 2B,F
.................... if (rovinka<MAX_ROVINKA) rovinka++;
003B: MOVF 2D,W
003C: SUBLW 40
003D: BTFSC 03.0
003E: INCF 2D,F
.................... }
.................... // Primitivni Pipani
003F: BCF 0C.1
0040: BCF 0A.3
0041: GOTO 022
.................... void beep(unsigned int16 period, unsigned int16 length)
.................... {
.................... unsigned int16 nn;
....................
.................... for(nn=length; nn>0; nn--)
*
0055: MOVF 60,W
0056: MOVWF 62
0057: MOVF 5F,W
0058: MOVWF 61
0059: MOVF 61,F
005A: BTFSS 03.2
005B: GOTO 05F
005C: MOVF 62,F
005D: BTFSC 03.2
005E: GOTO 07A
.................... {
.................... output_high(SOUND_HI);output_low(SOUND_LO);
005F: BSF 03.5
0060: BCF 05.6
0061: BCF 03.5
0062: BSF 05.6
0063: BSF 03.5
0064: BCF 05.7
0065: BCF 03.5
0066: BCF 05.7
.................... delay_us(period);
0067: MOVF 5D,W
0068: MOVWF 63
0069: CALL 042
.................... output_high(SOUND_LO);output_low(SOUND_HI);
006A: BSF 03.5
006B: BCF 05.7
006C: BCF 03.5
006D: BSF 05.7
006E: BSF 03.5
006F: BCF 05.6
0070: BCF 03.5
0071: BCF 05.6
.................... delay_us(period);
0072: MOVF 5D,W
0073: MOVWF 63
0074: CALL 042
.................... }
0075: MOVF 61,W
0076: BTFSC 03.2
0077: DECF 62,F
0078: DECF 61,F
0079: GOTO 059
.................... }
007A: RETLW 00
.................... /******************************************************************************/
.................... void diagnostika()
.................... {
.................... unsigned int16 n;
....................
.................... while (input(DIAG_SERVO)) // Propojka, ktera spousti diagnostiku
.................... {
*
0090: BSF 03.5
0091: BSF 06.3
0092: BCF 03.5
0093: BTFSS 06.3
0094: GOTO 1BB
.................... for (n=500; n<800; n+=100)
0095: MOVLW 01
0096: MOVWF 5C
0097: MOVLW F4
0098: MOVWF 5B
0099: MOVF 5C,W
009A: SUBLW 03
009B: BTFSS 03.0
009C: GOTO 0B1
009D: BTFSS 03.2
009E: GOTO 0A3
009F: MOVF 5B,W
00A0: SUBLW 1F
00A1: BTFSS 03.0
00A2: GOTO 0B1
.................... {
.................... beep(n,n); //beep UP
00A3: MOVF 5C,W
00A4: MOVWF 5E
00A5: MOVF 5B,W
00A6: MOVWF 5D
00A7: MOVF 5C,W
00A8: MOVWF 60
00A9: MOVF 5B,W
00AA: MOVWF 5F
00AB: CALL 055
.................... };
00AC: MOVLW 64
00AD: ADDWF 5B,F
00AE: BTFSC 03.0
00AF: INCF 5C,F
00B0: GOTO 099
.................... Delay_ms(1000);
00B1: MOVLW 04
00B2: MOVWF 5D
00B3: MOVLW FA
00B4: MOVWF 5E
00B5: CALL 07B
00B6: DECFSZ 5D,F
00B7: GOTO 0B3
.................... //zastav vse
.................... STOPL; STOPR;
00B8: BSF 03.5
00B9: BCF 06.6
00BA: BCF 03.5
00BB: BCF 06.6
00BC: BSF 03.5
00BD: BCF 06.7
00BE: BCF 03.5
00BF: BCF 06.7
00C0: BSF 03.5
00C1: BCF 06.4
00C2: BCF 03.5
00C3: BCF 06.4
00C4: BSF 03.5
00C5: BCF 06.5
00C6: BCF 03.5
00C7: BCF 06.5
.................... //pravy pas
.................... FR; Delay_ms(1000); STOPR; Delay_ms(1000);
00C8: BSF 03.5
00C9: BCF 06.5
00CA: BCF 03.5
00CB: BCF 06.5
00CC: BSF 03.5
00CD: BCF 06.4
00CE: BCF 03.5
00CF: BSF 06.4
00D0: MOVLW 04
00D1: MOVWF 5D
00D2: MOVLW FA
00D3: MOVWF 5E
00D4: CALL 07B
00D5: DECFSZ 5D,F
00D6: GOTO 0D2
00D7: BSF 03.5
00D8: BCF 06.4
00D9: BCF 03.5
00DA: BCF 06.4
00DB: BSF 03.5
00DC: BCF 06.5
00DD: BCF 03.5
00DE: BCF 06.5
00DF: MOVLW 04
00E0: MOVWF 5D
00E1: MOVLW FA
00E2: MOVWF 5E
00E3: CALL 07B
00E4: DECFSZ 5D,F
00E5: GOTO 0E1
.................... BR; Delay_ms(1000); STOPR; Delay_ms(1000);
00E6: BSF 03.5
00E7: BCF 06.4
00E8: BCF 03.5
00E9: BCF 06.4
00EA: BSF 03.5
00EB: BCF 06.5
00EC: BCF 03.5
00ED: BSF 06.5
00EE: MOVLW 04
00EF: MOVWF 5D
00F0: MOVLW FA
00F1: MOVWF 5E
00F2: CALL 07B
00F3: DECFSZ 5D,F
00F4: GOTO 0F0
00F5: BSF 03.5
00F6: BCF 06.4
00F7: BCF 03.5
00F8: BCF 06.4
00F9: BSF 03.5
00FA: BCF 06.5
00FB: BCF 03.5
00FC: BCF 06.5
00FD: MOVLW 04
00FE: MOVWF 5D
00FF: MOVLW FA
0100: MOVWF 5E
0101: CALL 07B
0102: DECFSZ 5D,F
0103: GOTO 0FF
.................... Beep(880,100); Delay_ms(1000);
0104: MOVLW 03
0105: MOVWF 5E
0106: MOVLW 70
0107: MOVWF 5D
0108: CLRF 60
0109: MOVLW 64
010A: MOVWF 5F
010B: CALL 055
010C: MOVLW 04
010D: MOVWF 5D
010E: MOVLW FA
010F: MOVWF 5E
0110: CALL 07B
0111: DECFSZ 5D,F
0112: GOTO 10E
.................... //levy pas
.................... FL; Delay_ms(1000); STOPL; Delay_ms(1000);
0113: BSF 03.5
0114: BCF 06.7
0115: BCF 03.5
0116: BCF 06.7
0117: BSF 03.5
0118: BCF 06.6
0119: BCF 03.5
011A: BSF 06.6
011B: MOVLW 04
011C: MOVWF 5D
011D: MOVLW FA
011E: MOVWF 5E
011F: CALL 07B
0120: DECFSZ 5D,F
0121: GOTO 11D
0122: BSF 03.5
0123: BCF 06.6
0124: BCF 03.5
0125: BCF 06.6
0126: BSF 03.5
0127: BCF 06.7
0128: BCF 03.5
0129: BCF 06.7
012A: MOVLW 04
012B: MOVWF 5D
012C: MOVLW FA
012D: MOVWF 5E
012E: CALL 07B
012F: DECFSZ 5D,F
0130: GOTO 12C
.................... BL; Delay_ms(1000); STOPL; Delay_ms(1000);
0131: BSF 03.5
0132: BCF 06.6
0133: BCF 03.5
0134: BCF 06.6
0135: BSF 03.5
0136: BCF 06.7
0137: BCF 03.5
0138: BSF 06.7
0139: MOVLW 04
013A: MOVWF 5D
013B: MOVLW FA
013C: MOVWF 5E
013D: CALL 07B
013E: DECFSZ 5D,F
013F: GOTO 13B
0140: BSF 03.5
0141: BCF 06.6
0142: BCF 03.5
0143: BCF 06.6
0144: BSF 03.5
0145: BCF 06.7
0146: BCF 03.5
0147: BCF 06.7
0148: MOVLW 04
0149: MOVWF 5D
014A: MOVLW FA
014B: MOVWF 5E
014C: CALL 07B
014D: DECFSZ 5D,F
014E: GOTO 14A
.................... Beep(880,100); Delay_ms(1000);
014F: MOVLW 03
0150: MOVWF 5E
0151: MOVLW 70
0152: MOVWF 5D
0153: CLRF 60
0154: MOVLW 64
0155: MOVWF 5F
0156: CALL 055
0157: MOVLW 04
0158: MOVWF 5D
0159: MOVLW FA
015A: MOVWF 5E
015B: CALL 07B
015C: DECFSZ 5D,F
015D: GOTO 159
.................... //oba pasy
.................... FL; FR; Delay_ms(1000); STOPL; STOPR; Delay_ms(1000);
015E: BSF 03.5
015F: BCF 06.7
0160: BCF 03.5
0161: BCF 06.7
0162: BSF 03.5
0163: BCF 06.6
0164: BCF 03.5
0165: BSF 06.6
0166: BSF 03.5
0167: BCF 06.5
0168: BCF 03.5
0169: BCF 06.5
016A: BSF 03.5
016B: BCF 06.4
016C: BCF 03.5
016D: BSF 06.4
016E: MOVLW 04
016F: MOVWF 5D
0170: MOVLW FA
0171: MOVWF 5E
0172: CALL 07B
0173: DECFSZ 5D,F
0174: GOTO 170
0175: BSF 03.5
0176: BCF 06.6
0177: BCF 03.5
0178: BCF 06.6
0179: BSF 03.5
017A: BCF 06.7
017B: BCF 03.5
017C: BCF 06.7
017D: BSF 03.5
017E: BCF 06.4
017F: BCF 03.5
0180: BCF 06.4
0181: BSF 03.5
0182: BCF 06.5
0183: BCF 03.5
0184: BCF 06.5
0185: MOVLW 04
0186: MOVWF 5D
0187: MOVLW FA
0188: MOVWF 5E
0189: CALL 07B
018A: DECFSZ 5D,F
018B: GOTO 187
.................... BL; BR; Delay_ms(1000); STOPL; STOPR; Delay_ms(1000);
018C: BSF 03.5
018D: BCF 06.6
018E: BCF 03.5
018F: BCF 06.6
0190: BSF 03.5
0191: BCF 06.7
0192: BCF 03.5
0193: BSF 06.7
0194: BSF 03.5
0195: BCF 06.4
0196: BCF 03.5
0197: BCF 06.4
0198: BSF 03.5
0199: BCF 06.5
019A: BCF 03.5
019B: BSF 06.5
019C: MOVLW 04
019D: MOVWF 5D
019E: MOVLW FA
019F: MOVWF 5E
01A0: CALL 07B
01A1: DECFSZ 5D,F
01A2: GOTO 19E
01A3: BSF 03.5
01A4: BCF 06.6
01A5: BCF 03.5
01A6: BCF 06.6
01A7: BSF 03.5
01A8: BCF 06.7
01A9: BCF 03.5
01AA: BCF 06.7
01AB: BSF 03.5
01AC: BCF 06.4
01AD: BCF 03.5
01AE: BCF 06.4
01AF: BSF 03.5
01B0: BCF 06.5
01B1: BCF 03.5
01B2: BCF 06.5
01B3: MOVLW 04
01B4: MOVWF 5D
01B5: MOVLW FA
01B6: MOVWF 5E
01B7: CALL 07B
01B8: DECFSZ 5D,F
01B9: GOTO 1B5
.................... };
01BA: GOTO 090
.................... while (input(DIAG_SENSORS)) // spusteni diagnostiky cidel
.................... {
01BB: BSF 03.5
01BC: BSF 06.2
01BD: BCF 03.5
01BE: BTFSS 06.2
01BF: GOTO 1EE
.................... if (RSENSOR) beep(1000,1000);
01C0: BSF 03.5
01C1: BTFSC 1C.7
01C2: GOTO 1CE
01C3: MOVLW 03
01C4: BCF 03.5
01C5: MOVWF 5E
01C6: MOVLW E8
01C7: MOVWF 5D
01C8: MOVLW 03
01C9: MOVWF 60
01CA: MOVLW E8
01CB: MOVWF 5F
01CC: CALL 055
01CD: BSF 03.5
.................... if (LSENSOR) beep(2000,2000);
01CE: BTFSC 1C.6
01CF: GOTO 1DB
01D0: MOVLW 07
01D1: BCF 03.5
01D2: MOVWF 5E
01D3: MOVLW D0
01D4: MOVWF 5D
01D5: MOVLW 07
01D6: MOVWF 60
01D7: MOVLW D0
01D8: MOVWF 5F
01D9: CALL 055
01DA: BSF 03.5
.................... if ((read_adc(ADC_READ_ONLY)<BUMPER_TRESHOLD)) beep(3000,3000);
01DB: BCF 03.5
01DC: BTFSS 1F.2
01DD: GOTO 1E0
01DE: BSF 03.5
01DF: GOTO 1DB
01E0: MOVF 1E,W
01E1: SUBLW 7F
01E2: BTFSS 03.0
01E3: GOTO 1ED
01E4: MOVLW 0B
01E5: MOVWF 5E
01E6: MOVLW B8
01E7: MOVWF 5D
01E8: MOVLW 0B
01E9: MOVWF 60
01EA: MOVLW B8
01EB: MOVWF 5F
01EC: CALL 055
.................... };
01ED: GOTO 1BB
.................... }
01EE: BCF 0A.3
01EF: GOTO 31F (RETURN)
.................... ///////////////////////////////////////////////////////////////////////////////
.................... void OtocSe() // otoci se zpet, kdyz je prekazka
.................... {
.................... unsigned int16 n;
....................
.................... BR;BL;
01F0: BSF 03.5
01F1: BCF 06.4
01F2: BCF 03.5
01F3: BCF 06.4
01F4: BSF 03.5
01F5: BCF 06.5
01F6: BCF 03.5
01F7: BSF 06.5
01F8: BSF 03.5
01F9: BCF 06.6
01FA: BCF 03.5
01FB: BCF 06.6
01FC: BSF 03.5
01FD: BCF 06.7
01FE: BCF 03.5
01FF: BSF 06.7
.................... beep(800,400);
0200: MOVLW 03
0201: MOVWF 5E
0202: MOVLW 20
0203: MOVWF 5D
0204: MOVLW 01
0205: MOVWF 60
0206: MOVLW 90
0207: MOVWF 5F
0208: CALL 055
.................... beep(2000,1000);
0209: MOVLW 07
020A: MOVWF 5E
020B: MOVLW D0
020C: MOVWF 5D
020D: MOVLW 03
020E: MOVWF 60
020F: MOVLW E8
0210: MOVWF 5F
0211: CALL 055
.................... beep(900,400);
0212: MOVLW 03
0213: MOVWF 5E
0214: MOVLW 84
0215: MOVWF 5D
0216: MOVLW 01
0217: MOVWF 60
0218: MOVLW 90
0219: MOVWF 5F
021A: CALL 055
....................
.................... BR; FL; Delay_ms(50); // otoc se 30° do prava
021B: BSF 03.5
021C: BCF 06.4
021D: BCF 03.5
021E: BCF 06.4
021F: BSF 03.5
0220: BCF 06.5
0221: BCF 03.5
0222: BSF 06.5
0223: BSF 03.5
0224: BCF 06.7
0225: BCF 03.5
0226: BCF 06.7
0227: BSF 03.5
0228: BCF 06.6
0229: BCF 03.5
022A: BSF 06.6
022B: MOVLW 32
022C: MOVWF 5E
022D: CALL 07B
.................... STOPL; STOPR;
022E: BSF 03.5
022F: BCF 06.6
0230: BCF 03.5
0231: BCF 06.6
0232: BSF 03.5
0233: BCF 06.7
0234: BCF 03.5
0235: BCF 06.7
0236: BSF 03.5
0237: BCF 06.4
0238: BCF 03.5
0239: BCF 06.4
023A: BSF 03.5
023B: BCF 06.5
023C: BCF 03.5
023D: BCF 06.5
.................... beep(1000,1000);
023E: MOVLW 03
023F: MOVWF 5E
0240: MOVLW E8
0241: MOVWF 5D
0242: MOVLW 03
0243: MOVWF 60
0244: MOVLW E8
0245: MOVWF 5F
0246: CALL 055
....................
.................... BR; FL;
0247: BSF 03.5
0248: BCF 06.4
0249: BCF 03.5
024A: BCF 06.4
024B: BSF 03.5
024C: BCF 06.5
024D: BCF 03.5
024E: BSF 06.5
024F: BSF 03.5
0250: BCF 06.7
0251: BCF 03.5
0252: BCF 06.7
0253: BSF 03.5
0254: BCF 06.6
0255: BCF 03.5
0256: BSF 06.6
.................... for(n=40000;n>0;n--) // toc se, dokud nenarazis na caru
0257: MOVLW 9C
0258: MOVWF 5C
0259: MOVLW 40
025A: MOVWF 5B
025B: MOVF 5B,F
025C: BTFSS 03.2
025D: GOTO 261
025E: MOVF 5C,F
025F: BTFSC 03.2
0260: GOTO 279
.................... {
.................... line = RSENSOR; // cteni senzoru na caru
0261: CLRF 2A
0262: BSF 03.5
0263: BTFSC 1C.7
0264: GOTO 268
0265: BCF 03.5
0266: INCF 2A,F
0267: BSF 03.5
.................... line |= LSENSOR << 1;
0268: MOVLW 00
0269: BTFSS 1C.6
026A: MOVLW 01
026B: MOVWF 77
026C: BCF 03.0
026D: RLF 77,F
026E: MOVF 77,W
026F: BCF 03.5
0270: IORWF 2A,F
.................... if (line!=0) break;
0271: MOVF 2A,F
0272: BTFSS 03.2
0273: GOTO 279
.................... }
0274: MOVF 5B,W
0275: BTFSC 03.2
0276: DECF 5C,F
0277: DECF 5B,F
0278: GOTO 25B
.................... STOPR; STOPL;
0279: BSF 03.5
027A: BCF 06.4
027B: BCF 03.5
027C: BCF 06.4
027D: BSF 03.5
027E: BCF 06.5
027F: BCF 03.5
0280: BCF 06.5
0281: BSF 03.5
0282: BCF 06.6
0283: BCF 03.5
0284: BCF 06.6
0285: BSF 03.5
0286: BCF 06.7
0287: BCF 03.5
0288: BCF 06.7
....................
.................... line=L; // caru jsme prejeli, tak je vlevo
0289: MOVLW 02
028A: MOVWF 2A
.................... cirkus=0;
028B: CLRF 2E
.................... }
028C: BCF 0A.3
028D: GOTO 34B (RETURN)
....................
....................
.................... void main()
.................... {
028E: CLRF 04
028F: MOVLW 1F
0290: ANDWF 03,F
0291: BSF 03.5
0292: BCF 1F.4
0293: BCF 1F.5
0294: MOVF 1B,W
0295: ANDLW 80
0296: MOVWF 1B
0297: MOVLW 07
0298: MOVWF 1C
0299: MOVF 1C,W
029A: BCF 03.5
029B: BCF 0D.6
029C: MOVLW 60
029D: BSF 03.5
029E: MOVWF 0F
.................... unsigned int16 n; // pro FOR
.................... unsigned int16 i;
....................
.................... STOPL; STOPR; // prepne vystupy na ovladani motoru na output a zastavi
029F: BCF 06.6
02A0: BCF 03.5
02A1: BCF 06.6
02A2: BSF 03.5
02A3: BCF 06.7
02A4: BCF 03.5
02A5: BCF 06.7
02A6: BSF 03.5
02A7: BCF 06.4
02A8: BCF 03.5
02A9: BCF 06.4
02AA: BSF 03.5
02AB: BCF 06.5
02AC: BCF 03.5
02AD: BCF 06.5
....................
.................... setup_oscillator(OSC_4MHZ|OSC_INTRC); // 4 MHz interni RC oscilator
02AE: MOVLW 62
02AF: BSF 03.5
02B0: MOVWF 0F
....................
.................... port_b_pullups(TRUE); // pullups pro piano na diagnostiku
02B1: BCF 01.7
.................... setup_spi(FALSE);
02B2: BCF 03.5
02B3: BCF 14.5
02B4: BSF 03.5
02B5: BCF 06.2
02B6: BSF 06.1
02B7: BCF 06.4
02B8: MOVLW 00
02B9: BCF 03.5
02BA: MOVWF 14
02BB: BSF 03.5
02BC: MOVWF 14
.................... setup_timer_0(RTCC_INTERNAL|RTCC_DIV_1); // Casovac pro PWM
02BD: MOVF 01,W
02BE: ANDLW C7
02BF: IORLW 08
02C0: MOVWF 01
....................
.................... setup_timer_2(T2_DIV_BY_4,255,10); // Casovac pro regulaci
02C1: MOVLW 48
02C2: MOVWF 78
02C3: IORLW 05
02C4: BCF 03.5
02C5: MOVWF 12
02C6: MOVLW FF
02C7: BSF 03.5
02C8: MOVWF 12
.................... // preruseni kazdych 10ms
.................... setup_adc_ports(sAN2|VSS_VDD); // nastaveni A/D prevodniku pro naraznik
02C9: BCF 1F.4
02CA: BCF 1F.5
02CB: MOVF 1B,W
02CC: ANDLW 80
02CD: IORLW 04
02CE: MOVWF 1B
.................... setup_adc(ADC_CLOCK_INTERNAL);
02CF: BCF 1F.6
02D0: BCF 03.5
02D1: BSF 1F.6
02D2: BSF 1F.7
02D3: BSF 03.5
02D4: BCF 1F.7
02D5: BCF 03.5
02D6: BSF 1F.0
.................... set_adc_channel(2);
02D7: MOVLW 10
02D8: MOVWF 78
02D9: MOVF 1F,W
02DA: ANDLW C7
02DB: IORWF 78,W
02DC: MOVWF 1F
.................... setup_timer_1(T1_INTERNAL|T1_DIV_BY_1); // Casovac pro naraznik
02DD: MOVLW 85
02DE: MOVWF 10
.................... setup_ccp1(CCP_COMPARE_RESET_TIMER);
02DF: BSF 03.5
02E0: BSF 06.3
02E1: MOVLW 0B
02E2: BCF 03.5
02E3: MOVWF 17
.................... CCP_1=(2^10)-1; // prevod kazdou 1ms
02E4: CLRF 16
02E5: MOVLW 07
02E6: MOVWF 15
....................
.................... setup_comparator(A0_VR_A1_VR); // inicializace komparatoru pro cidla cary
02E7: MOVLW 02
02E8: BSF 03.5
02E9: MOVWF 1C
02EA: MOVF 05,W
02EB: IORLW 03
02EC: MOVWF 05
02ED: MOVLW 03
02EE: MOVWF 77
02EF: DECFSZ 77,F
02F0: GOTO 2EF
02F1: MOVF 1C,W
02F2: BCF 03.5
02F3: BCF 0D.6
.................... setup_vref(VREF_HIGH|TRESHOLD); // 32 kroku od 0.25 do 0.75 Vdd
02F4: MOVLW 8F
02F5: BSF 03.5
02F6: MOVWF 1D
....................
.................... Beep(1000,200); //double beep
02F7: MOVLW 03
02F8: BCF 03.5
02F9: MOVWF 5E
02FA: MOVLW E8
02FB: MOVWF 5D
02FC: CLRF 60
02FD: MOVLW C8
02FE: MOVWF 5F
02FF: CALL 055
.................... Delay_ms(50);
0300: MOVLW 32
0301: MOVWF 5E
0302: CALL 07B
.................... Beep(1000,200);
0303: MOVLW 03
0304: MOVWF 5E
0305: MOVLW E8
0306: MOVWF 5D
0307: CLRF 60
0308: MOVLW C8
0309: MOVWF 5F
030A: CALL 055
.................... Delay_ms(1000); // 1s
030B: MOVLW 04
030C: MOVWF 5B
030D: MOVLW FA
030E: MOVWF 5E
030F: CALL 07B
0310: DECFSZ 5B,F
0311: GOTO 30D
....................
.................... // povoleni rizeni rychlosti zataceni pres preruseni
.................... enable_interrupts(INT_TIMER2);
0312: BSF 03.5
0313: BSF 0C.1
.................... enable_interrupts(GLOBAL);
0314: MOVLW C0
0315: BCF 03.5
0316: IORWF 0B,F
....................
.................... /*---------------------------------------------------------------------------*/
.................... sensors=S;
0317: MOVLW 03
0318: MOVWF 29
.................... line=S;
0319: MOVWF 2A
.................... last=S;
031A: MOVWF 2C
.................... cirkus=0;
031B: CLRF 2E
.................... // movement=S;
.................... speed=FW_POMALU;
031C: MOVLW AA
031D: MOVWF 2B
....................
.................... diagnostika();
031E: GOTO 090
.................... Delay_ms(500);
031F: MOVLW 02
0320: MOVWF 5B
0321: MOVLW FA
0322: MOVWF 5E
0323: CALL 07B
0324: DECFSZ 5B,F
0325: GOTO 321
.................... Beep(1000,200);
0326: MOVLW 03
0327: MOVWF 5E
0328: MOVLW E8
0329: MOVWF 5D
032A: CLRF 60
032B: MOVLW C8
032C: MOVWF 5F
032D: CALL 055
.................... Delay_ms(500);
032E: MOVLW 02
032F: MOVWF 5B
0330: MOVLW FA
0331: MOVWF 5E
0332: CALL 07B
0333: DECFSZ 5B,F
0334: GOTO 330
....................
.................... while(true) // hlavni smycka (jizda podle cary)
.................... {
.................... sensors = RSENSOR; // cteni senzoru na caru
0335: CLRF 29
0336: BSF 03.5
0337: BTFSC 1C.7
0338: GOTO 33C
0339: BCF 03.5
033A: INCF 29,F
033B: BSF 03.5
.................... sensors |= LSENSOR << 1;
033C: MOVLW 00
033D: BTFSS 1C.6
033E: MOVLW 01
033F: MOVWF 77
0340: BCF 03.0
0341: RLF 77,F
0342: MOVF 77,W
0343: BCF 03.5
0344: IORWF 29,F
....................
.................... if (read_adc(ADC_READ_ONLY)<BUMPER_TRESHOLD) OtocSe();
0345: BTFSC 1F.2
0346: GOTO 345
0347: MOVF 1E,W
0348: SUBLW 7F
0349: BTFSC 03.0
034A: GOTO 1F0
....................
.................... switch (sensors) // zatacej podle toho, kde vidis caru
.................... {
034B: MOVF 29,W
034C: XORLW 03
034D: BTFSC 03.2
034E: GOTO 356
034F: XORLW 01
0350: BTFSC 03.2
0351: GOTO 38B
0352: XORLW 03
0353: BTFSC 03.2
0354: GOTO 3C2
0355: GOTO 3F9
.................... case S: // rovne
.................... GO(L, F, FW_STREDNE+rovinka); GO(R, F, FW_STREDNE+rovinka);
0356: MOVF 01,W
0357: MOVWF 5B
0358: MOVLW BE
0359: ADDWF 2D,W
035A: SUBWF 5B,W
035B: BTFSC 03.2
035C: GOTO 35F
035D: BTFSC 03.0
035E: GOTO 368
035F: BSF 03.5
0360: BCF 06.7
0361: BCF 03.5
0362: BCF 06.7
0363: BSF 03.5
0364: BCF 06.6
0365: BCF 03.5
0366: BSF 06.6
0367: GOTO 370
0368: BSF 03.5
0369: BCF 06.6
036A: BCF 03.5
036B: BCF 06.6
036C: BSF 03.5
036D: BCF 06.7
036E: BCF 03.5
036F: BCF 06.7
0370: MOVF 01,W
0371: MOVWF 5B
0372: MOVLW BE
0373: ADDWF 2D,W
0374: SUBWF 5B,W
0375: BTFSC 03.2
0376: GOTO 379
0377: BTFSC 03.0
0378: GOTO 382
0379: BSF 03.5
037A: BCF 06.5
037B: BCF 03.5
037C: BCF 06.5
037D: BSF 03.5
037E: BCF 06.4
037F: BCF 03.5
0380: BSF 06.4
0381: GOTO 38A
0382: BSF 03.5
0383: BCF 06.4
0384: BCF 03.5
0385: BCF 06.4
0386: BSF 03.5
0387: BCF 06.5
0388: BCF 03.5
0389: BCF 06.5
.................... continue;
038A: GOTO 335
.................... case L: // trochu vlevo
.................... GO(L, F, FW_POMALU+rovinka); GO(R, F, FW_STREDNE+rovinka);
038B: MOVF 01,W
038C: MOVWF 5B
038D: MOVLW AA
038E: ADDWF 2D,W
038F: SUBWF 5B,W
0390: BTFSC 03.2
0391: GOTO 394
0392: BTFSC 03.0
0393: GOTO 39D
0394: BSF 03.5
0395: BCF 06.7
0396: BCF 03.5
0397: BCF 06.7
0398: BSF 03.5
0399: BCF 06.6
039A: BCF 03.5
039B: BSF 06.6
039C: GOTO 3A5
039D: BSF 03.5
039E: BCF 06.6
039F: BCF 03.5
03A0: BCF 06.6
03A1: BSF 03.5
03A2: BCF 06.7
03A3: BCF 03.5
03A4: BCF 06.7
03A5: MOVF 01,W
03A6: MOVWF 5B
03A7: MOVLW BE
03A8: ADDWF 2D,W
03A9: SUBWF 5B,W
03AA: BTFSC 03.2
03AB: GOTO 3AE
03AC: BTFSC 03.0
03AD: GOTO 3B7
03AE: BSF 03.5
03AF: BCF 06.5
03B0: BCF 03.5
03B1: BCF 06.5
03B2: BSF 03.5
03B3: BCF 06.4
03B4: BCF 03.5
03B5: BSF 06.4
03B6: GOTO 3BF
03B7: BSF 03.5
03B8: BCF 06.4
03B9: BCF 03.5
03BA: BCF 06.4
03BB: BSF 03.5
03BC: BCF 06.5
03BD: BCF 03.5
03BE: BCF 06.5
.................... line=L;
03BF: MOVLW 02
03C0: MOVWF 2A
.................... continue;
03C1: GOTO 335
.................... case R: // trochu vpravo
.................... GO(R, F, FW_POMALU+rovinka); GO(L, F, FW_STREDNE+rovinka);
03C2: MOVF 01,W
03C3: MOVWF 5B
03C4: MOVLW AA
03C5: ADDWF 2D,W
03C6: SUBWF 5B,W
03C7: BTFSC 03.2
03C8: GOTO 3CB
03C9: BTFSC 03.0
03CA: GOTO 3D4
03CB: BSF 03.5
03CC: BCF 06.5
03CD: BCF 03.5
03CE: BCF 06.5
03CF: BSF 03.5
03D0: BCF 06.4
03D1: BCF 03.5
03D2: BSF 06.4
03D3: GOTO 3DC
03D4: BSF 03.5
03D5: BCF 06.4
03D6: BCF 03.5
03D7: BCF 06.4
03D8: BSF 03.5
03D9: BCF 06.5
03DA: BCF 03.5
03DB: BCF 06.5
03DC: MOVF 01,W
03DD: MOVWF 5B
03DE: MOVLW BE
03DF: ADDWF 2D,W
03E0: SUBWF 5B,W
03E1: BTFSC 03.2
03E2: GOTO 3E5
03E3: BTFSC 03.0
03E4: GOTO 3EE
03E5: BSF 03.5
03E6: BCF 06.7
03E7: BCF 03.5
03E8: BCF 06.7
03E9: BSF 03.5
03EA: BCF 06.6
03EB: BCF 03.5
03EC: BSF 06.6
03ED: GOTO 3F6
03EE: BSF 03.5
03EF: BCF 06.6
03F0: BCF 03.5
03F1: BCF 06.6
03F2: BSF 03.5
03F3: BCF 06.7
03F4: BCF 03.5
03F5: BCF 06.7
.................... line=R;
03F6: MOVLW 01
03F7: MOVWF 2A
.................... continue;
03F8: GOTO 335
.................... default: // kdyz jsou obe cidla mimo caru, tak pokracuj dal
.................... };
.................... rovinka=0;
03F9: CLRF 2D
....................
.................... if (last!=line) // pokud si prejel caru z jedne strany na druhou stranu, tak zabrzdi
03FA: MOVF 2A,W
03FB: SUBWF 2C,W
03FC: BTFSC 03.2
03FD: GOTO 48F
.................... {
.................... last=line;
03FE: MOVF 2A,W
03FF: MOVWF 2C
.................... speed=FW_ZATACKA;
0400: MOVLW C8
0401: MOVWF 2B
.................... cirkus++;
0402: INCF 2E,F
.................... if (cirkus>10)
0403: MOVF 2E,W
0404: SUBLW 0A
0405: BTFSC 03.0
0406: GOTO 48F
.................... {
.................... STOPL; STOPR;
0407: BSF 03.5
0408: BCF 06.6
0409: BCF 03.5
040A: BCF 06.6
040B: BSF 03.5
040C: BCF 06.7
040D: BCF 03.5
040E: BCF 06.7
040F: BSF 03.5
0410: BCF 06.4
0411: BCF 03.5
0412: BCF 06.4
0413: BSF 03.5
0414: BCF 06.5
0415: BCF 03.5
0416: BCF 06.5
.................... cirkus=0;
0417: CLRF 2E
.................... disable_interrupts(GLOBAL);
0418: BCF 0B.6
0419: BCF 0B.7
041A: BTFSC 0B.7
041B: GOTO 419
.................... beep(1000,400);
041C: MOVLW 03
041D: MOVWF 5E
041E: MOVLW E8
041F: MOVWF 5D
0420: MOVLW 01
0421: MOVWF 60
0422: MOVLW 90
0423: MOVWF 5F
0424: CALL 055
.................... for(n=3000; n>3950; n--) beep(n,10);
0425: MOVLW 0B
0426: MOVWF 58
0427: MOVLW B8
0428: MOVWF 57
0429: MOVF 58,W
042A: SUBLW 0E
042B: BTFSC 03.0
042C: GOTO 441
042D: XORLW FF
042E: BTFSS 03.2
042F: GOTO 434
0430: MOVF 57,W
0431: SUBLW 6E
0432: BTFSC 03.0
0433: GOTO 441
0434: MOVF 58,W
0435: MOVWF 5E
0436: MOVF 57,W
0437: MOVWF 5D
0438: CLRF 60
0439: MOVLW 0A
043A: MOVWF 5F
043B: CALL 055
043C: MOVF 57,W
043D: BTFSC 03.2
043E: DECF 58,F
043F: DECF 57,F
0440: GOTO 429
.................... beep(2000,200);
0441: MOVLW 07
0442: MOVWF 5E
0443: MOVLW D0
0444: MOVWF 5D
0445: CLRF 60
0446: MOVLW C8
0447: MOVWF 5F
0448: CALL 055
.................... beep(900,400);
0449: MOVLW 03
044A: MOVWF 5E
044B: MOVLW 84
044C: MOVWF 5D
044D: MOVLW 01
044E: MOVWF 60
044F: MOVLW 90
0450: MOVWF 5F
0451: CALL 055
.................... for(n=2950; n<3000; n++) beep(n,10);
0452: MOVLW 0B
0453: MOVWF 58
0454: MOVLW 86
0455: MOVWF 57
0456: MOVF 58,W
0457: SUBLW 0B
0458: BTFSS 03.0
0459: GOTO 46C
045A: BTFSS 03.2
045B: GOTO 460
045C: MOVF 57,W
045D: SUBLW B7
045E: BTFSS 03.0
045F: GOTO 46C
0460: MOVF 58,W
0461: MOVWF 5E
0462: MOVF 57,W
0463: MOVWF 5D
0464: CLRF 60
0465: MOVLW 0A
0466: MOVWF 5F
0467: CALL 055
0468: INCF 57,F
0469: BTFSC 03.2
046A: INCF 58,F
046B: GOTO 456
.................... beep(4000,400);
046C: MOVLW 0F
046D: MOVWF 5E
046E: MOVLW A0
046F: MOVWF 5D
0470: MOVLW 01
0471: MOVWF 60
0472: MOVLW 90
0473: MOVWF 5F
0474: CALL 055
.................... beep(1000,100);
0475: MOVLW 03
0476: MOVWF 5E
0477: MOVLW E8
0478: MOVWF 5D
0479: CLRF 60
047A: MOVLW 64
047B: MOVWF 5F
047C: CALL 055
.................... beep(3000,400);
047D: MOVLW 0B
047E: MOVWF 5E
047F: MOVLW B8
0480: MOVWF 5D
0481: MOVLW 01
0482: MOVWF 60
0483: MOVLW 90
0484: MOVWF 5F
0485: CALL 055
.................... Delay_ms(1000);
0486: MOVLW 04
0487: MOVWF 5B
0488: MOVLW FA
0489: MOVWF 5E
048A: CALL 07B
048B: DECFSZ 5B,F
048C: GOTO 488
.................... enable_interrupts(GLOBAL);
048D: MOVLW C0
048E: IORWF 0B,F
.................... }
.................... };
....................
.................... if (L==line) // kdyz jsou obe cidla mimo caru, zatoc na caru
048F: MOVF 2A,W
0490: SUBLW 02
0491: BTFSS 03.2
0492: GOTO 4B1
.................... {
.................... STOPL;
0493: BSF 03.5
0494: BCF 06.6
0495: BCF 03.5
0496: BCF 06.6
0497: BSF 03.5
0498: BCF 06.7
0499: BCF 03.5
049A: BCF 06.7
.................... GO(R, F, speed);
049B: MOVF 01,W
049C: SUBWF 2B,W
049D: BTFSS 03.0
049E: GOTO 4A8
049F: BSF 03.5
04A0: BCF 06.5
04A1: BCF 03.5
04A2: BCF 06.5
04A3: BSF 03.5
04A4: BCF 06.4
04A5: BCF 03.5
04A6: BSF 06.4
04A7: GOTO 4B0
04A8: BSF 03.5
04A9: BCF 06.4
04AA: BCF 03.5
04AB: BCF 06.4
04AC: BSF 03.5
04AD: BCF 06.5
04AE: BCF 03.5
04AF: BCF 06.5
.................... }
.................... else
04B0: GOTO 4CE
.................... {
.................... STOPR;
04B1: BSF 03.5
04B2: BCF 06.4
04B3: BCF 03.5
04B4: BCF 06.4
04B5: BSF 03.5
04B6: BCF 06.5
04B7: BCF 03.5
04B8: BCF 06.5
.................... GO(L, F, speed);
04B9: MOVF 01,W
04BA: SUBWF 2B,W
04BB: BTFSS 03.0
04BC: GOTO 4C6
04BD: BSF 03.5
04BE: BCF 06.7
04BF: BCF 03.5
04C0: BCF 06.7
04C1: BSF 03.5
04C2: BCF 06.6
04C3: BCF 03.5
04C4: BSF 06.6
04C5: GOTO 4CE
04C6: BSF 03.5
04C7: BCF 06.6
04C8: BCF 03.5
04C9: BCF 06.6
04CA: BSF 03.5
04CB: BCF 06.7
04CC: BCF 03.5
04CD: BCF 06.7
.................... }
.................... } // while(true)
04CE: GOTO 335
.................... }
....................
04CF: SLEEP
 
Configuration Fuses:
Word 1: 3F38 NOWDT NOPUT MCLR NOBROWNOUT NOLVP NOCPD NOWRT NODEBUG CCPB0 NOPROTECT INTRC_IO
Word 2: 3FFC NOFCMEN NOIESO
/roboti/istrobot/merkur/PIC16F88/vystava/tank.PJT
0,0 → 1,40
[PROJECT]
Target=tank.HEX
Development_Mode=
Processor=0x688F
ToolSuite=CCS
 
[Directories]
Include=C:\Program Files\PICC\devices\;C:\Program Files\PICC\drivers\;C:\library\CCS;
Library=
LinkerScript=
 
[Target Data]
FileList=tank.c;
BuildTool=C-COMPILER
OptionString=+FM
AdditionalOptionString=
BuildRequired=1
 
[tank.c]
Type=4
Path=
FileList=
BuildTool=
OptionString=
AdditionalOptionString=
 
[mru-list]
1=tank.c
 
[Windows]
0=0000 tank.c 0 0 796 451 3 0
 
[Opened Files]
1=D:\KAKLIK\programy\PIC_C\roboti\merkur\PIC16F88\vystava\tank.c
2=D:\KAKL\PIC\MerkurI\tank.c
3=D:\KAKL\PIC\MerkurV\tank.c
4=D:\KAKLIK\programy\PIC_C\roboti\merkur\PIC16F88\turn_R\tank.c
5=
6=
7=
/roboti/istrobot/merkur/PIC16F88/vystava/tank.SYM
0,0 → 1,69
015-016 CCP_1
015 CCP_1_LOW
016 CCP_1_HIGH
020 @INTERRUPT_AREA
021 @INTERRUPT_AREA
022 @INTERRUPT_AREA
023 @INTERRUPT_AREA
024 @INTERRUPT_AREA
025 @INTERRUPT_AREA
026 @INTERRUPT_AREA
027 @INTERRUPT_AREA
028 @INTERRUPT_AREA
029 sensors
02A line
02B speed
02C last
02D rovinka
02E cirkus
02F-056 AXstring
057-058 main.n
059-05A main.i
05B-05C diagnostika.n
05B-05C OtocSe.n
05B main.@SCRATCH
05D-05E beep.period
05D diagnostika.@SCRATCH
05D OtocSe.@SCRATCH
05E @delay_ms1.P1
05F-060 beep.length
061-062 beep.nn
063 @delay_us1.P1
077 @SCRATCH
078 @SCRATCH
078 _RETURN_
079 @SCRATCH
07A @SCRATCH
07B @SCRATCH
09C.6 C1OUT
09C.7 C2OUT
 
007B @delay_ms1
0042 @delay_us1
0037 TIMER2_isr
0055 beep
0090 diagnostika
01F0 OtocSe
028E main
028E @cinit
 
Project Files:
D:\KAKLIK\programy\PIC_C\roboti\merkur\PIC16F88\vystava\tank.c
D:\KAKLIK\programy\PIC_C\roboti\merkur\PIC16F88\vystava\tank.h
C:\Program Files\PICC\devices\16F88.h
 
Compiler Settings:
Processor: PIC16F88
Pointer Size: 8
ADC Range: 0-255
Opt Level: 9
Short,Int,Long: 1,8,16
 
Output Files:
Errors: D:\KAKLIK\programy\PIC_C\roboti\merkur\PIC16F88\vystava\tank.err
INHX8: D:\KAKLIK\programy\PIC_C\roboti\merkur\PIC16F88\vystava\tank.HEX
Symbols: D:\KAKLIK\programy\PIC_C\roboti\merkur\PIC16F88\vystava\tank.SYM
List: D:\KAKLIK\programy\PIC_C\roboti\merkur\PIC16F88\vystava\tank.LST
Debug/COFF: D:\KAKLIK\programy\PIC_C\roboti\merkur\PIC16F88\vystava\tank.cof
Call Tree: D:\KAKLIK\programy\PIC_C\roboti\merkur\PIC16F88\vystava\tank.tre
Statistics: D:\KAKLIK\programy\PIC_C\roboti\merkur\PIC16F88\vystava\tank.sta
/roboti/istrobot/merkur/PIC16F88/vystava/tank.c
0,0 → 1,234
#include "tank.h"
 
unsigned int8 sensors; // pomocna promenna pro cteni cidel na caru
unsigned int8 line; // na ktere strane byla detekovana cara
unsigned int8 speed; // rychlost zataceni
unsigned int8 last; // kde byla cara, kdyz byly minule cidla mimo
unsigned int8 rovinka; // pocitadlo pro zjisteni rovneho useku
int cirkus;
 
// Konstanty pro dynamiku pohybu
#define T_DIRA 120 // po jakem case zataceni se detekuje dira
#define FW_POMALU 170 // trochu mimo caru vnitrni pas
#define FW_ZATACKA 200 // rychlost vnejsiho kola pri zataceni
#define FW_STREDNE 190 // trochu mimo caru vnejsi pas
#define COUVANI 750 // couvnuti zpet na caru, po detekci diry
#define MAX_ROVINKA (255-FW_STREDNE)
#define TRESHOLD 15 // rozhodovaci uroven komparatoru, 0xF = 0.75*Vdd
#define BUMPER_TRESHOLD 128
 
//motory //Napred vypnout potom zapnout!
#define FR output_low(PIN_B5); output_high(PIN_B4) // Vpred
#define FL output_low(PIN_B7); output_high(PIN_B6)
#define BR output_low(PIN_B4); output_high(PIN_B5) // Vzad
#define BL output_low(PIN_B6); output_high(PIN_B7)
#define STOPR output_low(PIN_B4);output_low(PIN_B5) // Zastav
#define STOPL output_low(PIN_B6);output_low(PIN_B7)
 
#define L 0b10 // left
#define R 0b01 // right
#define S 0b11 // straight
 
//cidla
#define RSENSOR !C2OUT // Senzory na caru
#define LSENSOR !C1OUT
#define BUMPER PIN_A4 // Senzor na cihlu
 
#define DIAG_SERVO PIN_B3 // Propojka pro diagnosticky mod
#define DIAG_SENSORS PIN_B2 // Propojka pro diagnosticky mod
 
#DEFINE SOUND_HI PIN_A6 // komplementarni vystupy pro piezo pipak
#DEFINE SOUND_LO PIN_A7
 
char AXstring[40]; // Buffer pro prenos telemetrie
 
// makro pro PWM
#define GO(motor, direction, power) if(get_timer0()<=power) \
{direction##motor;} else {stop##motor;}
 
#int_TIMER2
void TIMER2_isr()
{
if (speed<255) speed++;
if (rovinka<MAX_ROVINKA) rovinka++;
}
// Primitivni Pipani
void beep(unsigned int16 period, unsigned int16 length)
{
unsigned int16 nn;
 
for(nn=length; nn>0; nn--)
{
output_high(SOUND_HI);output_low(SOUND_LO);
delay_us(period);
output_high(SOUND_LO);output_low(SOUND_HI);
delay_us(period);
}
}
/******************************************************************************/
void diagnostika()
{
unsigned int16 n;
 
while (input(DIAG_SERVO)) // Propojka, ktera spousti diagnostiku
{
for (n=500; n<800; n+=100)
{
beep(n,n); //beep UP
};
Delay_ms(1000);
//zastav vse
STOPL; STOPR;
//pravy pas
FR; Delay_ms(1000); STOPR; Delay_ms(1000);
BR; Delay_ms(1000); STOPR; Delay_ms(1000);
Beep(880,100); Delay_ms(1000);
//levy pas
FL; Delay_ms(1000); STOPL; Delay_ms(1000);
BL; Delay_ms(1000); STOPL; Delay_ms(1000);
Beep(880,100); Delay_ms(1000);
//oba pasy
FL; FR; Delay_ms(1000); STOPL; STOPR; Delay_ms(1000);
BL; BR; Delay_ms(1000); STOPL; STOPR; Delay_ms(1000);
};
while (input(DIAG_SENSORS)) // spusteni diagnostiky cidel
{
if (RSENSOR) beep(1000,1000);
if (LSENSOR) beep(2000,2000);
if ((read_adc(ADC_READ_ONLY)<BUMPER_TRESHOLD)) beep(3000,3000);
};
}
///////////////////////////////////////////////////////////////////////////////
void OtocSe() // otoci se zpet, kdyz je prekazka
{
unsigned int16 n;
 
BR;BL;
beep(800,400);
beep(2000,1000);
beep(900,400);
 
BR; FL; Delay_ms(50); // otoc se 30° do prava
STOPL; STOPR;
beep(1000,1000);
 
BR; FL;
for(n=40000;n>0;n--) // toc se, dokud nenarazis na caru
{
line = RSENSOR; // cteni senzoru na caru
line |= LSENSOR << 1;
if (line!=0) break;
}
STOPR; STOPL;
 
line=L; // caru jsme prejeli, tak je vlevo
cirkus=0;
}
 
 
void main()
{
unsigned int16 n; // pro FOR
unsigned int16 i;
 
STOPL; STOPR; // prepne vystupy na ovladani motoru na output a zastavi
 
setup_oscillator(OSC_4MHZ|OSC_INTRC); // 4 MHz interni RC oscilator
 
port_b_pullups(TRUE); // pullups pro piano na diagnostiku
setup_spi(FALSE);
setup_timer_0(RTCC_INTERNAL|RTCC_DIV_1); // Casovac pro PWM
 
setup_timer_2(T2_DIV_BY_4,255,10); // Casovac pro regulaci
// preruseni kazdych 10ms
setup_adc_ports(sAN2|VSS_VDD); // nastaveni A/D prevodniku pro naraznik
setup_adc(ADC_CLOCK_INTERNAL);
set_adc_channel(2);
setup_timer_1(T1_INTERNAL|T1_DIV_BY_1); // Casovac pro naraznik
setup_ccp1(CCP_COMPARE_RESET_TIMER);
CCP_1=(2^10)-1; // prevod kazdou 1ms
 
setup_comparator(A0_VR_A1_VR); // inicializace komparatoru pro cidla cary
setup_vref(VREF_HIGH|TRESHOLD); // 32 kroku od 0.25 do 0.75 Vdd
 
Beep(1000,200); //double beep
Delay_ms(50);
Beep(1000,200);
Delay_ms(1000); // 1s
 
// povoleni rizeni rychlosti zataceni pres preruseni
enable_interrupts(INT_TIMER2);
enable_interrupts(GLOBAL);
 
/*---------------------------------------------------------------------------*/
sensors=S;
line=S;
last=S;
cirkus=0;
// movement=S;
speed=FW_POMALU;
 
diagnostika();
Delay_ms(500);
Beep(1000,200);
Delay_ms(500);
 
while(true) // hlavni smycka (jizda podle cary)
{
sensors = RSENSOR; // cteni senzoru na caru
sensors |= LSENSOR << 1;
 
if (read_adc(ADC_READ_ONLY)<BUMPER_TRESHOLD) OtocSe();
 
switch (sensors) // zatacej podle toho, kde vidis caru
{
case S: // rovne
GO(L, F, FW_STREDNE+rovinka); GO(R, F, FW_STREDNE+rovinka);
continue;
case L: // trochu vlevo
GO(L, F, FW_POMALU+rovinka); GO(R, F, FW_STREDNE+rovinka);
line=L;
continue;
case R: // trochu vpravo
GO(R, F, FW_POMALU+rovinka); GO(L, F, FW_STREDNE+rovinka);
line=R;
continue;
default: // kdyz jsou obe cidla mimo caru, tak pokracuj dal
};
rovinka=0;
 
if (last!=line) // pokud si prejel caru z jedne strany na druhou stranu, tak zabrzdi
{
last=line;
speed=FW_ZATACKA;
cirkus++;
if (cirkus>10)
{
STOPL; STOPR;
cirkus=0;
disable_interrupts(GLOBAL);
beep(1000,400);
for(n=3000; n>3950; n--) beep(n,10);
beep(2000,200);
beep(900,400);
for(n=2950; n<3000; n++) beep(n,10);
beep(4000,400);
beep(1000,100);
beep(3000,400);
Delay_ms(1000);
enable_interrupts(GLOBAL);
}
};
 
if (L==line) // kdyz jsou obe cidla mimo caru, zatoc na caru
{
STOPL;
GO(R, F, speed);
}
else
{
STOPR;
GO(L, F, speed);
}
} // while(true)
}
/roboti/istrobot/merkur/PIC16F88/vystava/tank.cof
Cannot display: file marked as a binary type.
svn:mime-type = application/octet-stream
Property changes:
Added: svn:mime-type
+application/octet-stream
\ No newline at end of property
/roboti/istrobot/merkur/PIC16F88/vystava/tank.err
0,0 → 1,0
No Errors
/roboti/istrobot/merkur/PIC16F88/vystava/tank.h
0,0 → 1,5
#include <16F88.h>
#device adc=8
#fuses NOWDT,INTRC_IO, NOPUT, MCLR, NOBROWNOUT, NOLVP, NOCPD, NOWRT, NODEBUG, NOPROTECT, NOFCMEN, NOIESO
#use delay(clock=4000000)
 
/roboti/istrobot/merkur/PIC16F88/vystava/tank.sta
0,0 → 1,35
 
ROM used: 1232 (30%)
1232 (30%) including unused fragments
 
2 Average locations per line
5 Average locations per statement
 
RAM used: 65 (37%) at main() level
73 (42%) worst case
 
Lines Stmts % Files
----- ----- --- -----
235 257 100 D:\KAKLIK\programy\PIC_C\roboti\merkur\PIC16F88\vystava\tank.c
6 0 0 D:\KAKLIK\programy\PIC_C\roboti\merkur\PIC16F88\vystava\tank.h
275 0 0 C:\Program Files\PICC\devices\16F88.h
----- -----
1032 514 Total
 
Page ROM % RAM Functions:
---- --- --- --- ----------
0 21 2 1 @delay_ms1
0 19 2 1 @delay_us1
0 11 1 0 TIMER2_isr
0 38 3 6 beep
0 352 29 3 diagnostika
0 158 13 3 OtocSe
0 578 47 5 main
 
Segment Used Free
--------- ---- ----
00000-00003 4 0
00004-00036 51 0
00037-007FF 1177 816
00800-00FFF 0 2048
 
/roboti/istrobot/merkur/PIC16F88/vystava/tank.tre
0,0 → 1,90
ÀÄtank
ÃÄmain 0/578 Ram=5
³ ÃÄ??0??
³ ÃÄbeep 0/38 Ram=6
³ ³ ÃÄ@delay_us1 0/19 Ram=1
³ ³ ÀÄ@delay_us1 0/19 Ram=1
³ ÃÄ@delay_ms1 0/21 Ram=1
³ ÃÄbeep 0/38 Ram=6
³ ³ ÃÄ@delay_us1 0/19 Ram=1
³ ³ ÀÄ@delay_us1 0/19 Ram=1
³ ÃÄ@delay_ms1 0/21 Ram=1
³ ÃÄdiagnostika 0/352 Ram=3
³ ³ ÃÄbeep 0/38 Ram=6
³ ³ ³ ÃÄ@delay_us1 0/19 Ram=1
³ ³ ³ ÀÄ@delay_us1 0/19 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄbeep 0/38 Ram=6
³ ³ ³ ÃÄ@delay_us1 0/19 Ram=1
³ ³ ³ ÀÄ@delay_us1 0/19 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄbeep 0/38 Ram=6
³ ³ ³ ÃÄ@delay_us1 0/19 Ram=1
³ ³ ³ ÀÄ@delay_us1 0/19 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄbeep 0/38 Ram=6
³ ³ ³ ÃÄ@delay_us1 0/19 Ram=1
³ ³ ³ ÀÄ@delay_us1 0/19 Ram=1
³ ³ ÃÄbeep 0/38 Ram=6
³ ³ ³ ÃÄ@delay_us1 0/19 Ram=1
³ ³ ³ ÀÄ@delay_us1 0/19 Ram=1
³ ³ ÀÄbeep 0/38 Ram=6
³ ³ ÃÄ@delay_us1 0/19 Ram=1
³ ³ ÀÄ@delay_us1 0/19 Ram=1
³ ÃÄ@delay_ms1 0/21 Ram=1
³ ÃÄbeep 0/38 Ram=6
³ ³ ÃÄ@delay_us1 0/19 Ram=1
³ ³ ÀÄ@delay_us1 0/19 Ram=1
³ ÃÄ@delay_ms1 0/21 Ram=1
³ ÃÄOtocSe 0/158 Ram=3
³ ³ ÃÄbeep 0/38 Ram=6
³ ³ ³ ÃÄ@delay_us1 0/19 Ram=1
³ ³ ³ ÀÄ@delay_us1 0/19 Ram=1
³ ³ ÃÄbeep 0/38 Ram=6
³ ³ ³ ÃÄ@delay_us1 0/19 Ram=1
³ ³ ³ ÀÄ@delay_us1 0/19 Ram=1
³ ³ ÃÄbeep 0/38 Ram=6
³ ³ ³ ÃÄ@delay_us1 0/19 Ram=1
³ ³ ³ ÀÄ@delay_us1 0/19 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÀÄbeep 0/38 Ram=6
³ ³ ÃÄ@delay_us1 0/19 Ram=1
³ ³ ÀÄ@delay_us1 0/19 Ram=1
³ ÃÄbeep 0/38 Ram=6
³ ³ ÃÄ@delay_us1 0/19 Ram=1
³ ³ ÀÄ@delay_us1 0/19 Ram=1
³ ÃÄbeep 0/38 Ram=6
³ ³ ÃÄ@delay_us1 0/19 Ram=1
³ ³ ÀÄ@delay_us1 0/19 Ram=1
³ ÃÄbeep 0/38 Ram=6
³ ³ ÃÄ@delay_us1 0/19 Ram=1
³ ³ ÀÄ@delay_us1 0/19 Ram=1
³ ÃÄbeep 0/38 Ram=6
³ ³ ÃÄ@delay_us1 0/19 Ram=1
³ ³ ÀÄ@delay_us1 0/19 Ram=1
³ ÃÄbeep 0/38 Ram=6
³ ³ ÃÄ@delay_us1 0/19 Ram=1
³ ³ ÀÄ@delay_us1 0/19 Ram=1
³ ÃÄbeep 0/38 Ram=6
³ ³ ÃÄ@delay_us1 0/19 Ram=1
³ ³ ÀÄ@delay_us1 0/19 Ram=1
³ ÃÄbeep 0/38 Ram=6
³ ³ ÃÄ@delay_us1 0/19 Ram=1
³ ³ ÀÄ@delay_us1 0/19 Ram=1
³ ÃÄbeep 0/38 Ram=6
³ ³ ÃÄ@delay_us1 0/19 Ram=1
³ ³ ÀÄ@delay_us1 0/19 Ram=1
³ ÀÄ@delay_ms1 0/21 Ram=1
ÀÄTIMER2_isr 0/11 Ram=0
/roboti/istrobot/merkur/PIC16F873/Kopie (2) - main.c
0,0 → 1,236
#include "main.h"
 
int movement; // smer minuleho pohybu
int line; // na ktere strane byla detekovana cara
unsigned int8 dira; // pocitadlo pro nalezeni preruseni cary
unsigned int8 speed; // rychlost zataceni
unsigned int8 straight; // pocitadlo pro zjisteni rovneho useku
 
// Konstanty pro dynamiku pohybu
#define T_DIRA 16 // po jakem case zataceni se detekuje dira
#define INC_SPEED 5 // prirustek rychlosti v jednom kroku
#define RIGHT_ANGLE 1000 // 90 stupnu
#define CIKCAK 20000 // 45 stupnu
#define BW_PO_DIRE 200 // zpetny chod po dire
#define FW_RYCHLE 200 // cara primo rovne
#define FW_POMALU 100 // trochu mimo caru vnitrni pas
#define FW_STREDNE 150 // trochu mimo caru vnejsi pas
#define TURN_MIN 90 // minimalni rychlost pri zataceni
#define TURN_MAX 150 // miximalni rychlost pri zataceni
#define BRZDENI 40 // doba zpetneho chodu v ms, aby pas stal
#define ROVINKA 8 // doba po kterou se musi jet rovne, aby se brzdilo
 
//motory //Napred vypnout potom zapnout!
#define FR output_low(PIN_B5); output_high(PIN_B4) // Vpred
#define FL output_low(PIN_B7); output_high(PIN_B6)
#define BR output_low(PIN_B4); output_high(PIN_B5) // Vzad
#define BL output_low(PIN_B6); output_high(PIN_B7)
#define STOPR output_low(PIN_B4);output_low(PIN_B5) // Zastav
#define STOPL output_low(PIN_B6);output_low(PIN_B7)
#define L 0b10 // left
#define R 0b01 // right
#define S 0b11 // straight
 
//cidla
#define RSENSOR 1 // Senzory na caru
#define LSENSOR 0
#define BUMPER PIN_C4 // Senzor na cihlu
 
#define DIAG_SERVO PIN_B0 // Propojka pro diagnosticky mod
#define DIAG_SENSORS PIN_B1 // Propojka pro diagnosticky mod
 
#DEFINE SOUND_HI PIN_B3 // komplementarni vystupy pro piezo pipak
#DEFINE SOUND_LO PIN_B2
 
char AXstring[40]; // Buffer pro prenos telemetrie
 
// makro pro PWM
#define GO(motor, direction, power) if(get_timer0()<=power) \
{direction##motor;} \
else \
{stop##motor;}
 
#int_TIMER1 // This function is called every time
void TIMER1_isr() { // the RTCC (timer0) overflows (255->0).
// For this program this is apx 76 times
// per second.
if (speed<TURN_MAX) speed+=INC_SPEED;
if (dira<255) dira++;
if (straight<255) straight++;
}
 
// Primitivni Pipani
void beep(unsigned int16 period, unsigned int16 length)
{
unsigned int16 nn;
 
for(nn=length; nn>0; nn--)
{
output_high(SOUND_HI);output_low(SOUND_LO);
delay_us(period);
output_high(SOUND_LO);output_low(SOUND_HI);
delay_us(period);
}
}
void diagnostika()
{
unsigned int16 n;
 
while (input(DIAG_SERVO)) // Propojka, ktera spousti diagnostiku
{
for (n=500; n<800; n+=100)
{
beep(n,n); //beep UP
};
Delay_ms(1000);
//zastav vse
STOPL; STOPR;
//pravy pas
FR; Delay_ms(1000); STOPR; Delay_ms(1000);
BR; Delay_ms(1000); STOPR; Delay_ms(1000);
Beep(880,100); Delay_ms(1000);
//levy pas
FL; Delay_ms(1000); STOPL; Delay_ms(1000);
BL; Delay_ms(1000); STOPL; Delay_ms(1000);
Beep(880,100); Delay_ms(1000);
//oba pasy
FL; FR; Delay_ms(1000); STOPL; STOPR; Delay_ms(1000);
BL; BR; Delay_ms(1000); STOPL; STOPR; Delay_ms(1000);
};
 
while (input(DIAG_SENSORS))
{
int ls, rs;
while(!input(BUMPER)){beep(1100,100); Delay_ms(50);}
set_adc_channel(RSENSOR);
Delay_us(20);
rs=read_adc();
set_adc_channel(LSENSOR);
Delay_us(20);
ls=read_adc();
};
}
void main()
{
STOPL; STOPR; // prepne vystupy na ovladani motoru na output a zastavi
setup_adc_ports(RA0_RA1_RA3_ANALOG);
setup_adc(ADC_CLOCK_DIV_2);
setup_timer_0(RTCC_INTERNAL|RTCC_DIV_1); // Casovac pro PWM
setup_timer_1(T1_INTERNAL|T1_DIV_BY_1); // Casovac pro regulaci
setup_timer_2(T2_DISABLED,0,1);
setup_ccp1(CCP_OFF);
diagnostika();
 
Beep(1000,200); //double beep
Delay_ms(50);
Beep(1000,200);
Delay_ms(1000); // 1s
 
 
speed=TURN_MIN; // povoleni rizeni rychlosti zataceni pres preruseni
enable_interrupts(INT_TIMER1);
enable_interrupts(GLOBAL);
 
// Cik-Cak -------------------------------------------------------------
line=S;
movement=R;
// cik_cak(); // toc se, abys nasel caru
Delay_ms(500);
Beep(1000,200);
Delay_ms(500);
 
dira=0; // inicializace globalnich promennych
straight=255;
 
while(true) // hlavni smycka (jizda podle cary)
{
set_adc_channel(LSENSOR); // kdyz cara nebyla pod pravym cidlem, mozna bude pod levym
Delay_us(10);
if(tresholdL > read_adc())
{
movement = L;
if (straight>ROVINKA)
{GO(R, F, FW_STREDNE+40); GO(L, F, FW_POMALU+40)} // pridej
else
{GO(R, F, FW_STREDNE); GO(L, F, FW_POMALU)};
speed=TURN_MIN;
dira=0;
line=L;
continue;
}
set_adc_channel(RSENSOR); // podivej se jestli neni cara pod pravym cidlem
Delay_us(10);
if(tresholdR > read_adc())
{
movement = R;
if (straight>ROVINKA)
{GO(L, F, FW_STREDNE+40); GO(R, F, FW_POMALU+40)} // pridej
else
{GO(L, F, FW_STREDNE); GO(R, F, FW_POMALU)};
speed=TURN_MIN;
dira=0;
line=R;
continue;
}
if(line==S)
movement = S;
if (straight>ROVINKA)
{FL; FR;} // pokud se jede dlouho rovne, tak pridej
else
{GO(R, F, FW_RYCHLE); GO(L, F, FW_RYCHLE)};
speed=TURN_MIN; // nastav minimalni rychlost pro zataceni
dira=0; // protoze byla cara, tak nuluj pocitadlo diry
continue;
 
 
if (straight>ROVINKA) // pokud byla dlouha rovinka, tak zabrzdi
{
BL; BR;
Delay_ms(BRZDENI);
STOPL;
STOPR;
dira=0;
};
straight=0; // nuluj pocitadlo rovinky
 
if (L==movement) // kdyz jsou obe cidla mimo caru, zatoc na caru
{
GO(R, F, speed);
STOPL;
}
else
{
GO(L, F, speed);
STOPR;
}
 
if (dira>T_DIRA) // pokud se moc dlouho zataci bez detekce cary, vrat se
{
STOPL;
STOPR;
Beep(1000,200); //double beep
Delay_ms(30);
Beep(2000,200);
Delay_ms(30);
if (L==movement) // zpet, podle toho kam se jelo
{
STOPL;
BR;
}
else
{
STOPR;
BL;
};
Delay_ms(BW_PO_DIRE);
STOPL;
STOPR;
cik_cak(); // najdi caru
dira=0;
}
 
} // while(true)
}
 
/roboti/istrobot/merkur/PIC16F873/main.BAK
0,0 → 1,332
#include "main.h"
 
#define TXo PIN_C3 // To the transmitter modulator
#include "AX25.c" // podprogram pro prenos telemetrie
 
//motory //Napred vypnout potom zapnout!
#define FR output_low(PIN_B5); output_high(PIN_B4) // Vpred
#define FL output_low(PIN_B7); output_high(PIN_B6)
#define BR output_low(PIN_B4); output_high(PIN_B5) // Vzad
#define BL output_low(PIN_B6); output_high(PIN_B7)
#define STOPR output_low(PIN_B4);output_low(PIN_B5)
#define STOPL output_low(PIN_B6);output_low(PIN_B7)
 
#define L 0b10 // left
#define R 0b01 // right
#define S 0b11 // straight
 
#define COUVANI 1600 // couvnuti po zjisteni diry
#define MEZERA 5400 // za jak dlouho bude ztracena cara
#define PRES_DIRU 400 // velikost mezery v care
#define ODEZVA 1 // za jak dlouho po opusteni cary se ma zacit zatacet
#define BRZDENI 90 // doba (v ms) ptrebna k zastaveni jednoho motoru
 
//cidla
#define RSENSOR 1 // Senzory na caru
#define LSENSOR 0
#define BUMPER PIN_C4 // sensor na cihlu
 
#define DIAG_SERVO PIN_B0 // Propojka pro diagnosticky mod
#define DIAG_SENSORS PIN_B1 // Propojka pro diagnosticky mod
 
#DEFINE SOUND_HI PIN_B3
#DEFINE SOUND_LO PIN_B2
 
char AXstring[40]; // Buffer pro prenos telemetrie
 
int tresholdL; // rozhodovaci uroven pro prave cidlo
int tresholdR; // rozhodovaci uroven pro prave cidlo
int movement; // smer minuleho pohybu
int line; // na ktere strane byla detekovana cara
unsigned int16 dira; // pocitadlo pro nalezeni preruseni cary
 
// Primitivni Pipani
void beep(unsigned int16 period, unsigned int16 length)
{
unsigned int16 nn;
 
for(nn=length; nn>0; nn--)
{
output_high(SOUND_HI);output_low(SOUND_LO);
delay_us(period);
output_high(SOUND_LO);output_low(SOUND_HI);
delay_us(period);
}
}
 
// Diagnostika pohonu, hejbne vsema motorama ve vsech smerech
void diagnostika()
{
unsigned int16 n;
 
while (input(DIAG_SERVO)) // Propojka, ktera spousti diagnostiku
{
for (n=500; n<800; n+=100)
{
beep(n,n); //beep UP
};
Delay_ms(1000);
//zastav vse
STOPL; STOPR;
//pravy pas
FR; Delay_ms(1000); STOPR; Delay_ms(1000);
BR; Delay_ms(1000); STOPR; Delay_ms(1000);
Beep(880,100); Delay_ms(1000);
//levy pas
FL; Delay_ms(1000); STOPL; Delay_ms(1000);
BL; Delay_ms(1000); STOPL; Delay_ms(1000);
Beep(880,100); Delay_ms(1000);
//oba pasy
FL; FR; Delay_ms(1000); STOPL; STOPR; Delay_ms(1000);
BL; BR; Delay_ms(1000); STOPL; STOPR; Delay_ms(1000);
};
 
while (input(DIAG_SENSORS))
{
int ls, rs;
while(!input(BUMPER)){beep(1100,100); Delay_ms(50);}
set_adc_channel(RSENSOR);
Delay_us(20);
rs=read_adc();
set_adc_channel(LSENSOR);
Delay_us(20);
ls=read_adc();
sprintf(AXstring,"L: %U R: %U\0", ls, rs); // Convert DATA to String.
SendPacket(&AXstring[0]);
delay_ms(1000);
};
}
 
void cikcak()
{
int n;
switch(movement) // podivej se na jednu stranu
{
case L:
FL;BR;
movement=R;
break;
case R:
FR;BL;
movement=L;
break;
case S:
FR;BL;
movement=L;
break;
}
set_adc_channel(LSENSOR);
Delay_us(10);
while (tresholdL < read_adc()) // je tam cara?
{
if (n==50) // asi bude na druhe strane
{
STOPR;STOPL;
n=0;
switch(movement)
{
case L:
FL;BR;
movement=R;
break;
case R:
FR;BL;
movement=L;
break;
}
}
Delay_ms(5);
n++;
}
STOPL;STOPR; // nasli jsme caru
line=S;
}
void objizdka()
{
BL;BR;Delay_ms(300);
STOPR;STOPL;
beep(1000,1000);
Delay_ms(500);
beep(1000,1000);
Delay_ms(1000);
 
}
void kalibrace()
{
unsigned int16 i;
int min;
int max;
int current;
int treshold;
 
FL; BR; Delay_ms(130);
chyba1:
FR; BL; //kalibrace leveho cidla
set_adc_channel(LSENSOR);
Delay_us(20);
min=max=read_adc();
for (i=1;i<=500;i++)
{
current=read_adc();
if (max < current) max=current;
if (min > current) min=current;
Delay_us(500);
}
FL; BR;
for (i=1;i<=500;i++)
{
current=read_adc();
if (max < current) max=current;
if (min > current) min=current;
Delay_us(500);
}
STOPL; STOPR; Delay_ms(200);
if((max-min)<50) {Beep(1000,300); GOTO chyba1;}
treshold=(max-min)>>1;
tresholdL=treshold+min;
 
chyba2:
FR; BL;
set_adc_channel(RSENSOR);
Delay_us(20);
min=max=read_adc(); //naplneni min a max nejakou rozumnou hodnotou
for (i=1;i<=500 ;i++)
{
current=read_adc();
if (max < current) max=current; //zmereni minima a maxima
if (min > current) min=current;
Delay_us(500);
}
FL; BR;
for (i=1;i<=500 ;i++)
{
current=read_adc();
if (max < current) max=current; //zmereni minima a maxima
if (min > current) min=current;
Delay_us(500);
}
STOPL; STOPR; Delay_ms(200);
if((max-min)<50) {Beep(1000,300); GOTO chyba2;}
treshold=(max-min)>>1;
tresholdR=treshold+min;
 
FR; BL;
movement=L;
set_adc_channel(LSENSOR);
Delay_us(20);
while (tresholdL < read_adc()) Delay_us(100);
FL; BR; Delay_ms(50);
STOPL; STOPR; Delay_ms(500);
Beep(780,200);
}
 
void main()
{
unsigned int16 rovne; // pocita delku rovne cary
 
STOPL; STOPR;
 
setup_adc_ports(RA0_RA1_RA3_ANALOG);
setup_adc(ADC_CLOCK_DIV_2);
 
port_b_pullups(false);
 
diagnostika();
 
Beep(1000,200); //double beep
Delay_ms(50);
Beep(1000,200);
Delay_ms(1000); // 1s
 
// kalibrace();
tresholdl=tresholdr=80;
// FL; FR;
movement=S;
line=S;
dira=0;
rovne=0;
 
while(true)
{
if(!input(BUMPER)) objizdka();
line=0;
set_adc_channel(RSENSOR); // podivej se jestli neni cara pod pravym cidlem
Delay_us(10);
if(tresholdR > read_adc())
{
dira=0;
line=R;
}
set_adc_channel(LSENSOR); // kdyz cara nebyla pod pravym cidlem, mozna bude pod levym
Delay_us(10);
if(tresholdL > read_adc())
{
dira=0;
line=line | L;
}
switch(line)
{
case S:
FR;FL;
movement=S;
continue;
case L:
STOPL;
FR;movement=L;
continue;
case R:
STOPR;
FL;movement=R;
continue;
default:
}
 
if (dira==ODEZVA) // kdyz uz chvili jedeme po bile plose
{
//BR;BL;Delay_us(rovne >>= 5);
rovne=0; //kdyz sme museli zatocit, uz neni rovna cara
 
switch (line) // musime zatocit
{
case L:
BL;Delay_ms(BRZDENI);STOPL;
FR;
movement=L;
break;
case R:
BR;Delay_ms(BRZDENI);STOPR;
FL;
movement=R;
break;
}
}
if (dira==MEZERA) // kdyz zkoncila cara
{
beep(800,500);
Delay_ms(50);
beep(800,500);
switch (movement) //vrat se zpet na caru
{
case L:
STOPL;STOPR;
BR;Delay_ms(COUVANI);STOPR;
break;
case R:
STOPL;STOPR;
BL;Delay_ms(COUVANI);STOPL;
break;
case S:
BL; BR; Delay_ms(COUVANI);
STOPL; STOPR;
break;
}
 
FR;FL; Delay_ms(PRES_DIRU); // popojedem dopredu mozna tam bude cara
STOPL; STOPR; movement=S;
cikcak(); // najdi caru
dira=0;
}
dira++;
} // while(true)
}
/roboti/istrobot/merkur/PIC16F873/main.HEX
0,0 → 1,200
:1000000000308A001D2C00000A108A100A11820795
:100010004C343A342034253455342034203452348E
:100020003A34203425345534003400347830840098
:10003000FC308005800C800C00080319232821283F
:100040000000800B202800347508F7007408F600C3
:10005000F608031D2E28F708031949288316861170
:100060008312861583160611831206117208F80092
:100070001620831606118312061583168611831225
:1000800086117208F800162076080319F703F603A4
:100090002828003473308400000803195E280130DA
:1000A000A100A001A00B5228A10B51284A30A000AA
:1000B000A00B582800000000800B4F2800346B086C
:1000C000840075088000840A8001EB0A00347608F9
:1000D000A101750203186F287508A0007B28A001F4
:1000E0000830F700F50DA00D760820020318A000D7
:1000F000A10DF70B7228003421087308F500643055
:10010000F60067202008F30021083030031D8F28F7
:100110007418F415F4199528741A20309128F411E4
:100120007412A1072108F5005F207308F5000A305A
:10013000F60067202008F30021083030031DA428B2
:10014000F419A828741A2030A1072108F5005F20AF
:100150003030F3077308F5005F200034B801351C18
:10016000B3283510B42835140034351CE828BC11E8
:100170003C0883168700831287154930A000A00B26
:10018000BF2800000000BC113C08831687008312C2
:1001900087114930A000A00BCB2800000000BC1143
:1001A0003C0883168700831287154930A000A00BF6
:1001B000D72800000000BC113C088316870083127A
:1001C00087111930A000A00BE32800000000FE28D2
:1001D000BC113C0883168700831287158930A00064
:1001E000A00BF028BC113C088316870083128711EE
:1001F0007230A000A00BFA28000000000034F501C6
:100200007508073C031C492974080139F600BA082F
:1002100003190C2900300D290130F700B908031922
:1002200013290030142901307705003A03192729D2
:100230007608F7000310B70CB60C030801397706EF
:10024000013C031D27298430B7060830B606F6089E
:10025000031D2C29AE204429B908031D3029B80AF2
:10026000B90803193529003036290130F70038085C
:10027000053C03193D2900303E2901307705003A3D
:1002800003194429B520AE20B5200310F40CF50A5B
:1002900000290034831606148312061C752A0130C7
:1002A000EF00F430EE006F08033C031C6B29031DC4
:1002B0005D296E081F3C031C6B296F08F3006E0854
:1002C000F2006F08F5006E08F40024206430EE0799
:1002D0000318EF0A53290430F200FA30F3004A20E1
:1002E000F20B6D29831606138312061383168613E9
:1002F0008312861383160612831206128316861241
:1003000083128612831686128312861283160612B1
:10031000831206160430F200FA30F3004A20F20B82
:100320008C298316061283120612831686128312F4
:1003300086120430F200FA30F3004A20F20B9B29B7
:1003400083160612831206128316861283128616ED
:100350000430F200FA30F3004A20F20BAA29831687
:100360000612831206128316861283128612043036
:10037000F200FA30F3004A20F20BB9290330F300FF
:100380007030F200F5016430F40024200430F200F3
:10039000FA30F3004A20F20BC82983168613831221
:1003A000861383160613831206170430F200FA3000
:1003B000F3004A20F20BD729831606138312061383
:1003C00083168613831286130430F200FA30F3008A
:1003D0004A20F20BE62983160613831206138316AE
:1003E0008613831286170430F200FA30F3004A2095
:1003F000F20BF52983160613831206138316861350
:10040000831286130430F200FA30F3004A20F20B14
:10041000042A0330F3007030F200F5016430F40078
:1004200024200430F200FA30F3004A20F20B132AA1
:1004300083168613831286138316061383120617F8
:1004400083168612831286128316061283120616EC
:100450000430F200FA30F3004A20F20B2A2A831605
:1004600006138312061383168613831286138316CC
:100470000612831206128316861283128612043025
:10048000F200FA30F3004A20F20B412A83160613D9
:100490008312061383168613831286178316061299
:1004A0008312061283168612831286160430F20017
:1004B000FA30F3004A20F20B582A831606138312EF
:1004C000061383168613831286138316061283126D
:1004D000061283168612831286120430F200FA3056
:1004E000F3004A20F20B6F2A4A29831686148312DE
:1004F000861C192B3C163C08831687008312071AAA
:100500008D2A0430F3004C30F200F5016430F40021
:1005100024203230F3004A207A2A0830A1001F0834
:10052000C73921049F000630A000A00B952A0000C7
:100530001F151F19992A1E08F1000030A1001F087D
:10054000C73921049F000630A000A00BA52A000097
:100550001F151F19A92A1E08F0003D30EB004C3072
:10056000F5005F203A30F5005F202030F5005F2075
:100570007008F3001830F4007C200530F200720897
:100580000420F20AF5005F200A307202031DBF2A20
:100590007108F3001830F4007C203D30F200351073
:1005A000FF30B700B600B8010130B900BA01BB0195
:1005B0003B08093C031CE12A7E30F400FF20BB0A03
:1005C000D82AB901BB013B080F3C031CF02A253097
:1005D0003B0784000008F300F400FF20BB0AE32A75
:1005E000BB01720884000008003A0319002B72084E
:1005F00084000008F300F400FF20F20ABB0AF12A8D
:100600000130BA00FF30B606B7063608F400FF2006
:100610003708F400FF20BA010130B9007E30F40041
:10062000FF200430F200FA30F3004A20F20B132BC3
:10063000752A8A115E2C83160613831206138316FD
:1006400086138312861783160612831206128316E8
:100650008612831286160230EE009630F3004A208E
:10066000EE0B2D2B831606128312061283168612AA
:1006700083128612831606138312061383168613BB
:10068000831286130330F300E830F2000330F500E4
:10069000E830F40024200230EE00FA30F3004A2063
:1006A000EE0B4D2B0330F300E830F2000330F50081
:1006B000E830F40024200430EE00FA30F3004A2041
:1006C000EE0B5D2B8A118A2C01306702FD3E031868
:1006D000A42B033E102C83168613831286138316D5
:1006E0000613831206178316061283120612831648
:1006F0008612831286160130E700A42B8316861219
:1007000083128612831606128312061683160613A8
:100710008312061383168613831286170230E700AE
:10072000A42B831686128312861283160612831256
:100730000616831606138312061383168613831276
:1007400086170230E700A42B0030A1001F08C7392C
:1007500021049F000330A000A00BAC2B1F151F1914
:10076000AF2B1E0865020318FC2B6E08323C031DDC
:10077000F72B831606128312061283168612831233
:1007800086128316061383120613831686138312AA
:100790008613EE0101306702FE3E0318F72B023E7E
:1007A000172C83168613831286138316061383125F
:1007B00006178316061283120612831686128312F8
:1007C00086160130E700F72B8316861283128612F5
:1007D0008316061283120616831606138312061357
:1007E00083168613831286170230E700F72B053035
:1007F000F3004A20EE0AAE2B83160613831206136B
:10080000831686138312861383160612831206122A
:1008100083168612831286120330E8008A11102E86
:100820000A108A100A1582077E2B6B2B912B0A1057
:100830008A100A158207E42BD12B84011F3083050F
:10084000073083169F0082308312A5009830A600DF
:10085000A7004030A800A900AA006030AB00863095
:10086000AC00B430AD006030AE00A430AF00B000DA
:10087000B1006130B2000330B300F030B400FF309B
:10088000BC00EB018316061383120613831686132E
:10089000831286138316061283120612831686129B
:1008A00083128612043083169F0083121F08383982
:1008B00001389F008316811783124A290330F30001
:1008C000E830F200F501C830F40024203230F300A3
:1008D0004A200330F300E830F200F501C830F4009C
:1008E00024200430EE00FA30F3004A20EE0B732C83
:1008F0005030E600E5000330E700E800EA01E901D6
:10090000ED01EC013C163C08831687008312071AA0
:100910008A2C1B2BE8010830A1001F08C7392104CD
:100920009F000330A000A00B932C1F151F19962CBD
:100930001E0866020319A22C031CA22CEA01E9017D
:100940000130E8000030A1001F08C73921049F00D2
:100950000330A000A00BAA2C1F151F19AD2C1E08D8
:1009600065020319B82C031CB82CEA01E901E8144C
:100970006808A000033020020319C72C02302002AF
:100980000319DA2C013020020319ED2C002D8316F7
:100990008612831286128316061283120616831697
:1009A00086138312861383160613831206170330E9
:1009B000E700822C83160613831206138316861310
:1009C00083128613831686128312861283160612EA
:1009D000831206160230E700822C83160612831259
:1009E00006128316861283128612831686138312CA
:1009F000861383160613831206170130E700822C34
:100A0000690B4A2DEA08031D4A2DED01EC01013066
:100A10006802FE3E03184A2D023E172E8316061367
:100A20008312061383168613831286176430F3002D
:100A30004A20831606138312061383168613831225
:100A40008613831686128312861283160612831269
:100A500006160230E7004A2D83160612831206128C
:100A600083168612831286166430F3004A2083169A
:100A700006128312061283168612831286128316BA
:100A8000861383128613831606138312061701300A
:100A9000E7004A2D6908183C031D122E6A08153C10
:100AA000031D122E0330F3002030F2000130F50058
:100AB000F430F40024203230F3004A200330F300F5
:100AC0002030F2000130F500F430F4002420013031
:100AD0006702FD3E0318E62D033E1D2E8316061306
:100AE0008312061383168613831286138316061247
:100AF000831206128316861283128612831606123A
:100B00008312061283168612831286160830EE00B0
:100B1000C830F3004A20EE0B882D8316061283128C
:100B200006128316861283128612E62D831606138A
:100B300083120613831686138312861383160612F6
:100B400083120612831686128312861283160613E8
:100B50008312061383168613831286170830EE005D
:100B6000C830F3004A20EE0BB02D83160613831213
:100B700006138316861383128613E62D8316061337
:100B800083120613831686138312861783160612A2
:100B90008312061283168612831286160830EE0020
:100BA000C830F3004A20EE0BD02D831606138312B3
:100BB0000613831686138312861383160612831276
:100BC00006128316861283128612E62D831686126B
:100BD0008312861283160612831206168316861354
:100BE0008312861383160613831206170230EE0053
:100BF000C830F3004A20EE0BF82D8316061383123B
:100C00000613831686138312861383160612831225
:100C1000061283168612831286120330E700642BB5
:100C2000EA01E901E90A0319EA0A822C63000A10C1
:100C30008A140A1582072C2D0E2D0A108A140A1503
:080C40008207962D6E2DBE2DDA
:02400E00793FF8
:00000001FF
;PIC16F873
/roboti/istrobot/merkur/PIC16F873/main.LST
0,0 → 1,2057
CCS PCW C Compiler, Version 3.110, 15448
 
Filename: d:\kaklik\programy\pic_c\roboti\merkur\main.LST
 
ROM used: 1572 (38%)
Largest free fragment is 2048
RAM used: 79 (41%) at main() level
90 (47%) worst case
Stack: 3 locations
 
*
0000: MOVLW 00
0001: MOVWF 0A
0002: GOTO 41D
0003: NOP
.................... #include "main.h"
.................... #include <16F873.h>
.................... //////// Standard Header file for the PIC16F873 device ////////////////
.................... #device PIC16F873
.................... #list
....................
.................... #device adc=8
.................... #use delay(clock=4000000)
*
0016: MOVLW 78
0017: MOVWF 04
0018: MOVLW FC
0019: ANDWF 00,F
001A: RRF 00,F
001B: RRF 00,F
001C: MOVF 00,W
001D: BTFSC 03.2
001E: GOTO 023
001F: GOTO 021
0020: NOP
0021: DECFSZ 00,F
0022: GOTO 020
0023: RETLW 00
*
004A: MOVLW 73
004B: MOVWF 04
004C: MOVF 00,W
004D: BTFSC 03.2
004E: GOTO 05E
004F: MOVLW 01
0050: MOVWF 21
0051: CLRF 20
0052: DECFSZ 20,F
0053: GOTO 052
0054: DECFSZ 21,F
0055: GOTO 051
0056: MOVLW 4A
0057: MOVWF 20
0058: DECFSZ 20,F
0059: GOTO 058
005A: NOP
005B: NOP
005C: DECFSZ 00,F
005D: GOTO 04F
005E: RETLW 00
.................... #fuses XT,NOWDT,NOLVP
....................
....................
....................
.................... #define TXo PIN_C3 // To the transmitter modulator
.................... #include "AX25.c" // podprogram pro prenos telemetrie
.................... //#define PTT PIN_A2 // PTT control
.................... //#define TXo PIN_C0 // To the transmitter modulator
.................... #define PERIODAH delay_us(222) // Halfperiod H 222;78/1200 500;430/500
.................... #define TAILH delay_us(78)
.................... #define PERIODAL delay_us(412) // Halfperiod L 412;345/1200 1000;880/500
.................... #define TAILL delay_us(345)
.................... #byte STATUS = 3 // CPUs status register
....................
.................... byte SendData[16] = {'A'<<1, 'L'<<1, 'L'<<1, ' '<<1, ' '<<1, ' '<<1, 0x60,
.................... 'C'<<1, 'Z'<<1, '0'<<1, 'R'<<1, 'R'<<1, 'R'<<1, 0x61,
.................... 0x03, 0xF0};
....................
.................... boolean bit;
.................... int fcslo, fcshi; // variabloes for calculating FCS (CRC)
.................... int stuff; // stuff counter for extra 0
.................... int flag_flag; // if it is sending flag (7E)
.................... int fcs_flag; // if it is sending Frame Check Sequence
.................... int i; // for for
....................
.................... void flipout() //flips the state of output pin a_1
.................... {
.................... stuff = 0; //since this is a 0, reset the stuff counter
*
00AE: CLRF 38
.................... if (bit)
00AF: BTFSS 35.0
00B0: GOTO 0B3
.................... {
.................... bit=FALSE; //if the state of the pin was low, make it high.
00B1: BCF 35.0
.................... }
.................... else
00B2: GOTO 0B4
.................... {
.................... bit=TRUE; //if the state of the pin was high make it low
00B3: BSF 35.0
.................... }
00B4: RETLW 00
.................... }
....................
.................... void fcsbit(byte tbyte)
.................... {
.................... #asm
.................... BCF STATUS,0
*
011A: BCF 03.0
.................... RRF fcshi,F // rotates the entire 16 bits
011B: RRF 37,F
.................... RRF fcslo,F // to the right
.................... #endasm
011C: RRF 36,F
.................... if (((STATUS & 0x01)^(tbyte)) ==0x01)
011D: MOVF 03,W
011E: ANDLW 01
011F: XORWF 77,W
0120: SUBLW 01
0121: BTFSS 03.2
0122: GOTO 127
.................... {
.................... fcshi = fcshi^0x84;
0123: MOVLW 84
0124: XORWF 37,F
.................... fcslo = fcslo^0x08;
0125: MOVLW 08
0126: XORWF 36,F
.................... }
.................... }
....................
.................... void SendBit ()
.................... {
.................... if (bit)
*
00B5: BTFSS 35.0
00B6: GOTO 0E8
.................... {
.................... output_high(TXo);
00B7: BCF 3C.3
00B8: MOVF 3C,W
00B9: BSF 03.5
00BA: MOVWF 07
00BB: BCF 03.5
00BC: BSF 07.3
.................... PERIODAH;
00BD: MOVLW 49
00BE: MOVWF 20
00BF: DECFSZ 20,F
00C0: GOTO 0BF
00C1: NOP
00C2: NOP
.................... output_low(TXo);
00C3: BCF 3C.3
00C4: MOVF 3C,W
00C5: BSF 03.5
00C6: MOVWF 07
00C7: BCF 03.5
00C8: BCF 07.3
.................... PERIODAH;
00C9: MOVLW 49
00CA: MOVWF 20
00CB: DECFSZ 20,F
00CC: GOTO 0CB
00CD: NOP
00CE: NOP
.................... output_high(TXo);
00CF: BCF 3C.3
00D0: MOVF 3C,W
00D1: BSF 03.5
00D2: MOVWF 07
00D3: BCF 03.5
00D4: BSF 07.3
.................... PERIODAH;
00D5: MOVLW 49
00D6: MOVWF 20
00D7: DECFSZ 20,F
00D8: GOTO 0D7
00D9: NOP
00DA: NOP
.................... output_low(TXo);
00DB: BCF 3C.3
00DC: MOVF 3C,W
00DD: BSF 03.5
00DE: MOVWF 07
00DF: BCF 03.5
00E0: BCF 07.3
.................... TAILH;
00E1: MOVLW 19
00E2: MOVWF 20
00E3: DECFSZ 20,F
00E4: GOTO 0E3
00E5: NOP
00E6: NOP
.................... }
.................... else
00E7: GOTO 0FE
.................... {
.................... output_high(TXo);
00E8: BCF 3C.3
00E9: MOVF 3C,W
00EA: BSF 03.5
00EB: MOVWF 07
00EC: BCF 03.5
00ED: BSF 07.3
.................... PERIODAL;
00EE: MOVLW 89
00EF: MOVWF 20
00F0: DECFSZ 20,F
00F1: GOTO 0F0
.................... output_low(TXo);
00F2: BCF 3C.3
00F3: MOVF 3C,W
00F4: BSF 03.5
00F5: MOVWF 07
00F6: BCF 03.5
00F7: BCF 07.3
.................... TAILL;
00F8: MOVLW 72
00F9: MOVWF 20
00FA: DECFSZ 20,F
00FB: GOTO 0FA
00FC: NOP
00FD: NOP
.................... };
00FE: RETLW 00
.................... }
....................
.................... void SendByte (byte inbyte)
.................... {
.................... int k, bt;
....................
.................... for (k=0;k<8;k++) //do the following for each of the 8 bits in the byte
00FF: CLRF 75
0100: MOVF 75,W
0101: SUBLW 07
0102: BTFSS 03.0
0103: GOTO 149
.................... {
.................... bt = inbyte & 0x01; //strip off the rightmost bit of the byte to be sent (inbyte)
0104: MOVF 74,W
0105: ANDLW 01
0106: MOVWF 76
.................... if ((fcs_flag == FALSE) & (flag_flag == FALSE)) fcsbit(bt); //do FCS calc, but only if this
0107: MOVF 3A,F
0108: BTFSC 03.2
0109: GOTO 10C
010A: MOVLW 00
010B: GOTO 10D
010C: MOVLW 01
010D: MOVWF 77
010E: MOVF 39,F
010F: BTFSC 03.2
0110: GOTO 113
0111: MOVLW 00
0112: GOTO 114
0113: MOVLW 01
0114: ANDWF 77,W
0115: XORLW 00
0116: BTFSC 03.2
0117: GOTO 127
0118: MOVF 76,W
0119: MOVWF 77
.................... //is not a flag or fcs byte
.................... if (bt == 0)
*
0127: MOVF 76,F
0128: BTFSS 03.2
0129: GOTO 12C
.................... {
.................... flipout();
012A: CALL 0AE
.................... } // if this bit is a zero, flip the output state
.................... else
012B: GOTO 144
.................... { //otherwise if it is a 1, do the following:
.................... if (flag_flag == FALSE) stuff++; //increment the count of consequtive 1's
012C: MOVF 39,F
012D: BTFSS 03.2
012E: GOTO 130
012F: INCF 38,F
.................... if ((flag_flag == FALSE) & (stuff == 5))
0130: MOVF 39,F
0131: BTFSC 03.2
0132: GOTO 135
0133: MOVLW 00
0134: GOTO 136
0135: MOVLW 01
0136: MOVWF 77
0137: MOVF 38,W
0138: SUBLW 05
0139: BTFSC 03.2
013A: GOTO 13D
013B: MOVLW 00
013C: GOTO 13E
013D: MOVLW 01
013E: ANDWF 77,W
013F: XORLW 00
0140: BTFSC 03.2
0141: GOTO 144
.................... { //stuff an extra 0, if 5 1's in a row
.................... SendBit();
0142: CALL 0B5
.................... flipout(); //flip the output state to stuff a 0
0143: CALL 0AE
.................... }//end of if
.................... }//end of else
.................... // delay_us(850); //introduces a delay that creates 1200 baud
.................... SendBit();
0144: CALL 0B5
.................... inbyte = inbyte>>1; //go to the next bit in the byte
0145: BCF 03.0
0146: RRF 74,F
.................... }//end of for
0147: INCF 75,F
0148: GOTO 100
0149: RETLW 00
.................... }//end of SendByte
....................
.................... void SendPacket(char *data)
.................... {
.................... bit=FALSE;
*
02CF: BCF 35.0
....................
.................... fcslo=fcshi=0xFF; //The 2 FCS Bytes are initialized to FF
02D0: MOVLW FF
02D1: MOVWF 37
02D2: MOVWF 36
.................... stuff = 0; //The variable stuff counts the number of 1's in a row. When it gets to 5
02D3: CLRF 38
.................... // it is time to stuff a 0.
....................
.................... // output_low(PTT); // Blinking LED
.................... // delay_ms(1000);
.................... // output_high(PTT);
....................
.................... flag_flag = TRUE; //The variable flag is true if you are transmitted flags (7E's) false otherwise.
02D4: MOVLW 01
02D5: MOVWF 39
.................... fcs_flag = FALSE; //The variable fcsflag is true if you are transmitting FCS bytes, false otherwise.
02D6: CLRF 3A
....................
.................... for(i=0; i<10; i++) SendByte(0x7E); //Sends flag bytes. Adjust length for txdelay
02D7: CLRF 3B
02D8: MOVF 3B,W
02D9: SUBLW 09
02DA: BTFSS 03.0
02DB: GOTO 2E1
02DC: MOVLW 7E
02DD: MOVWF 74
02DE: CALL 0FF
02DF: INCF 3B,F
02E0: GOTO 2D8
.................... //each flag takes approx 6.7 ms
.................... flag_flag = FALSE; //done sending flags
02E1: CLRF 39
....................
.................... for(i=0; i<16; i++) SendByte(SendData[i]); //send the packet bytes
02E2: CLRF 3B
02E3: MOVF 3B,W
02E4: SUBLW 0F
02E5: BTFSS 03.0
02E6: GOTO 2F0
02E7: MOVLW 25
02E8: ADDWF 3B,W
02E9: MOVWF 04
02EA: MOVF 00,W
02EB: MOVWF 73
02EC: MOVWF 74
02ED: CALL 0FF
02EE: INCF 3B,F
02EF: GOTO 2E3
....................
.................... for(i=0; 0 != *data; i++)
02F0: CLRF 3B
02F1: MOVF 72,W
02F2: MOVWF 04
02F3: MOVF 00,W
02F4: XORLW 00
02F5: BTFSC 03.2
02F6: GOTO 300
.................... {
.................... SendByte(*data); //send the packet bytes
02F7: MOVF 72,W
02F8: MOVWF 04
02F9: MOVF 00,W
02FA: MOVWF 73
02FB: MOVWF 74
02FC: CALL 0FF
.................... data++;
02FD: INCF 72,F
.................... };
02FE: INCF 3B,F
02FF: GOTO 2F1
....................
.................... fcs_flag = TRUE; //about to send the FCS bytes
0300: MOVLW 01
0301: MOVWF 3A
.................... fcslo =fcslo^0xff; //must XOR them with FF before sending
0302: MOVLW FF
0303: XORWF 36,F
.................... fcshi = fcshi^0xff;
0304: XORWF 37,F
.................... SendByte(fcslo); //send the low byte of fcs
0305: MOVF 36,W
0306: MOVWF 74
0307: CALL 0FF
.................... SendByte(fcshi); //send the high byte of fcs
0308: MOVF 37,W
0309: MOVWF 74
030A: CALL 0FF
.................... fcs_flag = FALSE; //done sending FCS
030B: CLRF 3A
.................... flag_flag = TRUE; //about to send flags
030C: MOVLW 01
030D: MOVWF 39
.................... SendByte(0x7e); // Send a flag to end packet
030E: MOVLW 7E
030F: MOVWF 74
0310: CALL 0FF
.................... }
....................
....................
....................
....................
....................
.................... //motory //Napred vypnout potom zapnout!
.................... #define FR output_low(PIN_B5); output_high(PIN_B4) // Vpred
.................... #define FL output_low(PIN_B7); output_high(PIN_B6)
.................... #define BR output_low(PIN_B4); output_high(PIN_B5) // Vzad
.................... #define BL output_low(PIN_B6); output_high(PIN_B7)
.................... #define STOPR output_low(PIN_B4);output_low(PIN_B5)
.................... #define STOPL output_low(PIN_B6);output_low(PIN_B7)
....................
.................... #define L 0b10 // left
.................... #define R 0b01 // right
.................... #define S 0b11 // straight
....................
.................... #define COUVANI 1600 // couvnuti po zjisteni diry
.................... #define MEZERA 5400 // za jak dlouho bude ztracena cara
.................... #define PRES_DIRU 400 // velikost mezery v care
.................... #define ODEZVA 1 // za jak dlouho po opusteni cary se ma zacit zatacet
.................... #define BRZDENI 100 // doba (v ms) ptrebna k zastaveni jednoho motoru
....................
.................... //cidla
.................... #define RSENSOR 1 // Senzory na caru
.................... #define LSENSOR 0
.................... #define BUMPER PIN_C4 // sensor na cihlu
....................
.................... #define DIAG_SERVO PIN_B0 // Propojka pro diagnosticky mod
.................... #define DIAG_SENSORS PIN_B1 // Propojka pro diagnosticky mod
....................
.................... #DEFINE SOUND_HI PIN_B3
.................... #DEFINE SOUND_LO PIN_B2
....................
.................... char AXstring[40]; // Buffer pro prenos telemetrie
....................
.................... int tresholdL; // rozhodovaci uroven pro prave cidlo
.................... int tresholdR; // rozhodovaci uroven pro prave cidlo
.................... int movement; // smer minuleho pohybu
.................... int line; // na ktere strane byla detekovana cara
.................... unsigned int16 dira; // pocitadlo pro nalezeni preruseni cary
....................
.................... // Primitivni Pipani
.................... void beep(unsigned int16 period, unsigned int16 length)
.................... {
.................... unsigned int16 nn;
....................
.................... for(nn=length; nn>0; nn--)
*
0024: MOVF 75,W
0025: MOVWF 77
0026: MOVF 74,W
0027: MOVWF 76
0028: MOVF 76,F
0029: BTFSS 03.2
002A: GOTO 02E
002B: MOVF 77,F
002C: BTFSC 03.2
002D: GOTO 049
.................... {
.................... output_high(SOUND_HI);output_low(SOUND_LO);
002E: BSF 03.5
002F: BCF 06.3
0030: BCF 03.5
0031: BSF 06.3
0032: BSF 03.5
0033: BCF 06.2
0034: BCF 03.5
0035: BCF 06.2
.................... delay_us(period);
0036: MOVF 72,W
0037: MOVWF 78
0038: CALL 016
.................... output_high(SOUND_LO);output_low(SOUND_HI);
0039: BSF 03.5
003A: BCF 06.2
003B: BCF 03.5
003C: BSF 06.2
003D: BSF 03.5
003E: BCF 06.3
003F: BCF 03.5
0040: BCF 06.3
.................... delay_us(period);
0041: MOVF 72,W
0042: MOVWF 78
0043: CALL 016
.................... }
0044: MOVF 76,W
0045: BTFSC 03.2
0046: DECF 77,F
0047: DECF 76,F
0048: GOTO 028
0049: RETLW 00
.................... }
....................
.................... // Diagnostika pohonu, hejbne vsema motorama ve vsech smerech
.................... void diagnostika()
.................... {
.................... unsigned int16 n;
....................
.................... while (input(DIAG_SERVO)) // Propojka, ktera spousti diagnostiku
*
014A: BSF 03.5
014B: BSF 06.0
014C: BCF 03.5
014D: BTFSS 06.0
014E: GOTO 275
.................... {
.................... for (n=500; n<800; n+=100)
014F: MOVLW 01
0150: MOVWF 6F
0151: MOVLW F4
0152: MOVWF 6E
0153: MOVF 6F,W
0154: SUBLW 03
0155: BTFSS 03.0
0156: GOTO 16B
0157: BTFSS 03.2
0158: GOTO 15D
0159: MOVF 6E,W
015A: SUBLW 1F
015B: BTFSS 03.0
015C: GOTO 16B
.................... {
.................... beep(n,n); //beep UP
015D: MOVF 6F,W
015E: MOVWF 73
015F: MOVF 6E,W
0160: MOVWF 72
0161: MOVF 6F,W
0162: MOVWF 75
0163: MOVF 6E,W
0164: MOVWF 74
0165: CALL 024
.................... };
0166: MOVLW 64
0167: ADDWF 6E,F
0168: BTFSC 03.0
0169: INCF 6F,F
016A: GOTO 153
.................... Delay_ms(1000);
016B: MOVLW 04
016C: MOVWF 72
016D: MOVLW FA
016E: MOVWF 73
016F: CALL 04A
0170: DECFSZ 72,F
0171: GOTO 16D
.................... //zastav vse
.................... STOPL; STOPR;
0172: BSF 03.5
0173: BCF 06.6
0174: BCF 03.5
0175: BCF 06.6
0176: BSF 03.5
0177: BCF 06.7
0178: BCF 03.5
0179: BCF 06.7
017A: BSF 03.5
017B: BCF 06.4
017C: BCF 03.5
017D: BCF 06.4
017E: BSF 03.5
017F: BCF 06.5
0180: BCF 03.5
0181: BCF 06.5
.................... //pravy pas
.................... FR; Delay_ms(1000); STOPR; Delay_ms(1000);
0182: BSF 03.5
0183: BCF 06.5
0184: BCF 03.5
0185: BCF 06.5
0186: BSF 03.5
0187: BCF 06.4
0188: BCF 03.5
0189: BSF 06.4
018A: MOVLW 04
018B: MOVWF 72
018C: MOVLW FA
018D: MOVWF 73
018E: CALL 04A
018F: DECFSZ 72,F
0190: GOTO 18C
0191: BSF 03.5
0192: BCF 06.4
0193: BCF 03.5
0194: BCF 06.4
0195: BSF 03.5
0196: BCF 06.5
0197: BCF 03.5
0198: BCF 06.5
0199: MOVLW 04
019A: MOVWF 72
019B: MOVLW FA
019C: MOVWF 73
019D: CALL 04A
019E: DECFSZ 72,F
019F: GOTO 19B
.................... BR; Delay_ms(1000); STOPR; Delay_ms(1000);
01A0: BSF 03.5
01A1: BCF 06.4
01A2: BCF 03.5
01A3: BCF 06.4
01A4: BSF 03.5
01A5: BCF 06.5
01A6: BCF 03.5
01A7: BSF 06.5
01A8: MOVLW 04
01A9: MOVWF 72
01AA: MOVLW FA
01AB: MOVWF 73
01AC: CALL 04A
01AD: DECFSZ 72,F
01AE: GOTO 1AA
01AF: BSF 03.5
01B0: BCF 06.4
01B1: BCF 03.5
01B2: BCF 06.4
01B3: BSF 03.5
01B4: BCF 06.5
01B5: BCF 03.5
01B6: BCF 06.5
01B7: MOVLW 04
01B8: MOVWF 72
01B9: MOVLW FA
01BA: MOVWF 73
01BB: CALL 04A
01BC: DECFSZ 72,F
01BD: GOTO 1B9
.................... Beep(880,100); Delay_ms(1000);
01BE: MOVLW 03
01BF: MOVWF 73
01C0: MOVLW 70
01C1: MOVWF 72
01C2: CLRF 75
01C3: MOVLW 64
01C4: MOVWF 74
01C5: CALL 024
01C6: MOVLW 04
01C7: MOVWF 72
01C8: MOVLW FA
01C9: MOVWF 73
01CA: CALL 04A
01CB: DECFSZ 72,F
01CC: GOTO 1C8
.................... //levy pas
.................... FL; Delay_ms(1000); STOPL; Delay_ms(1000);
01CD: BSF 03.5
01CE: BCF 06.7
01CF: BCF 03.5
01D0: BCF 06.7
01D1: BSF 03.5
01D2: BCF 06.6
01D3: BCF 03.5
01D4: BSF 06.6
01D5: MOVLW 04
01D6: MOVWF 72
01D7: MOVLW FA
01D8: MOVWF 73
01D9: CALL 04A
01DA: DECFSZ 72,F
01DB: GOTO 1D7
01DC: BSF 03.5
01DD: BCF 06.6
01DE: BCF 03.5
01DF: BCF 06.6
01E0: BSF 03.5
01E1: BCF 06.7
01E2: BCF 03.5
01E3: BCF 06.7
01E4: MOVLW 04
01E5: MOVWF 72
01E6: MOVLW FA
01E7: MOVWF 73
01E8: CALL 04A
01E9: DECFSZ 72,F
01EA: GOTO 1E6
.................... BL; Delay_ms(1000); STOPL; Delay_ms(1000);
01EB: BSF 03.5
01EC: BCF 06.6
01ED: BCF 03.5
01EE: BCF 06.6
01EF: BSF 03.5
01F0: BCF 06.7
01F1: BCF 03.5
01F2: BSF 06.7
01F3: MOVLW 04
01F4: MOVWF 72
01F5: MOVLW FA
01F6: MOVWF 73
01F7: CALL 04A
01F8: DECFSZ 72,F
01F9: GOTO 1F5
01FA: BSF 03.5
01FB: BCF 06.6
01FC: BCF 03.5
01FD: BCF 06.6
01FE: BSF 03.5
01FF: BCF 06.7
0200: BCF 03.5
0201: BCF 06.7
0202: MOVLW 04
0203: MOVWF 72
0204: MOVLW FA
0205: MOVWF 73
0206: CALL 04A
0207: DECFSZ 72,F
0208: GOTO 204
.................... Beep(880,100); Delay_ms(1000);
0209: MOVLW 03
020A: MOVWF 73
020B: MOVLW 70
020C: MOVWF 72
020D: CLRF 75
020E: MOVLW 64
020F: MOVWF 74
0210: CALL 024
0211: MOVLW 04
0212: MOVWF 72
0213: MOVLW FA
0214: MOVWF 73
0215: CALL 04A
0216: DECFSZ 72,F
0217: GOTO 213
.................... //oba pasy
.................... FL; FR; Delay_ms(1000); STOPL; STOPR; Delay_ms(1000);
0218: BSF 03.5
0219: BCF 06.7
021A: BCF 03.5
021B: BCF 06.7
021C: BSF 03.5
021D: BCF 06.6
021E: BCF 03.5
021F: BSF 06.6
0220: BSF 03.5
0221: BCF 06.5
0222: BCF 03.5
0223: BCF 06.5
0224: BSF 03.5
0225: BCF 06.4
0226: BCF 03.5
0227: BSF 06.4
0228: MOVLW 04
0229: MOVWF 72
022A: MOVLW FA
022B: MOVWF 73
022C: CALL 04A
022D: DECFSZ 72,F
022E: GOTO 22A
022F: BSF 03.5
0230: BCF 06.6
0231: BCF 03.5
0232: BCF 06.6
0233: BSF 03.5
0234: BCF 06.7
0235: BCF 03.5
0236: BCF 06.7
0237: BSF 03.5
0238: BCF 06.4
0239: BCF 03.5
023A: BCF 06.4
023B: BSF 03.5
023C: BCF 06.5
023D: BCF 03.5
023E: BCF 06.5
023F: MOVLW 04
0240: MOVWF 72
0241: MOVLW FA
0242: MOVWF 73
0243: CALL 04A
0244: DECFSZ 72,F
0245: GOTO 241
.................... BL; BR; Delay_ms(1000); STOPL; STOPR; Delay_ms(1000);
0246: BSF 03.5
0247: BCF 06.6
0248: BCF 03.5
0249: BCF 06.6
024A: BSF 03.5
024B: BCF 06.7
024C: BCF 03.5
024D: BSF 06.7
024E: BSF 03.5
024F: BCF 06.4
0250: BCF 03.5
0251: BCF 06.4
0252: BSF 03.5
0253: BCF 06.5
0254: BCF 03.5
0255: BSF 06.5
0256: MOVLW 04
0257: MOVWF 72
0258: MOVLW FA
0259: MOVWF 73
025A: CALL 04A
025B: DECFSZ 72,F
025C: GOTO 258
025D: BSF 03.5
025E: BCF 06.6
025F: BCF 03.5
0260: BCF 06.6
0261: BSF 03.5
0262: BCF 06.7
0263: BCF 03.5
0264: BCF 06.7
0265: BSF 03.5
0266: BCF 06.4
0267: BCF 03.5
0268: BCF 06.4
0269: BSF 03.5
026A: BCF 06.5
026B: BCF 03.5
026C: BCF 06.5
026D: MOVLW 04
026E: MOVWF 72
026F: MOVLW FA
0270: MOVWF 73
0271: CALL 04A
0272: DECFSZ 72,F
0273: GOTO 26F
.................... };
0274: GOTO 14A
....................
.................... while (input(DIAG_SENSORS))
0275: BSF 03.5
0276: BSF 06.1
0277: BCF 03.5
0278: BTFSS 06.1
0279: GOTO 319
.................... {
.................... int ls, rs;
.................... while(!input(BUMPER)){beep(1100,100); Delay_ms(50);}
027A: BSF 3C.4
027B: MOVF 3C,W
027C: BSF 03.5
027D: MOVWF 07
027E: BCF 03.5
027F: BTFSC 07.4
0280: GOTO 28D
0281: MOVLW 04
0282: MOVWF 73
0283: MOVLW 4C
0284: MOVWF 72
0285: CLRF 75
0286: MOVLW 64
0287: MOVWF 74
0288: CALL 024
0289: MOVLW 32
028A: MOVWF 73
028B: CALL 04A
028C: GOTO 27A
.................... set_adc_channel(RSENSOR);
028D: MOVLW 08
028E: MOVWF 21
028F: MOVF 1F,W
0290: ANDLW C7
0291: IORWF 21,W
0292: MOVWF 1F
.................... Delay_us(20);
0293: MOVLW 06
0294: MOVWF 20
0295: DECFSZ 20,F
0296: GOTO 295
0297: NOP
.................... rs=read_adc();
0298: BSF 1F.2
0299: BTFSC 1F.2
029A: GOTO 299
029B: MOVF 1E,W
029C: MOVWF 71
.................... set_adc_channel(LSENSOR);
029D: MOVLW 00
029E: MOVWF 21
029F: MOVF 1F,W
02A0: ANDLW C7
02A1: IORWF 21,W
02A2: MOVWF 1F
.................... Delay_us(20);
02A3: MOVLW 06
02A4: MOVWF 20
02A5: DECFSZ 20,F
02A6: GOTO 2A5
02A7: NOP
.................... ls=read_adc();
02A8: BSF 1F.2
02A9: BTFSC 1F.2
02AA: GOTO 2A9
02AB: MOVF 1E,W
02AC: MOVWF 70
.................... sprintf(AXstring,"L: %U R: %U\0", ls, rs); // Convert DATA to String.
*
0004: BCF 0A.0
0005: BCF 0A.1
0006: BCF 0A.2
0007: ADDWF 02,F
0008: RETLW 4C
0009: RETLW 3A
000A: RETLW 20
000B: RETLW 25
000C: RETLW 55
000D: RETLW 20
000E: RETLW 20
000F: RETLW 52
0010: RETLW 3A
0011: RETLW 20
0012: RETLW 25
0013: RETLW 55
0014: RETLW 00
0015: RETLW 00
*
007C: MOVF 21,W
007D: MOVF 73,W
007E: MOVWF 75
007F: MOVLW 64
0080: MOVWF 76
0081: CALL 067
0082: MOVF 20,W
0083: MOVWF 73
0084: MOVF 21,W
0085: MOVLW 30
0086: BTFSS 03.2
0087: GOTO 08F
0088: BTFSC 74.0
0089: BSF 74.3
008A: BTFSC 74.3
008B: GOTO 095
008C: BTFSC 74.4
008D: MOVLW 20
008E: GOTO 091
008F: BCF 74.3
0090: BCF 74.4
0091: ADDWF 21,F
0092: MOVF 21,W
0093: MOVWF 75
0094: CALL 05F
0095: MOVF 73,W
0096: MOVWF 75
0097: MOVLW 0A
0098: MOVWF 76
0099: CALL 067
009A: MOVF 20,W
009B: MOVWF 73
009C: MOVF 21,W
009D: MOVLW 30
009E: BTFSS 03.2
009F: GOTO 0A4
00A0: BTFSC 74.3
00A1: GOTO 0A8
00A2: BTFSC 74.4
00A3: MOVLW 20
00A4: ADDWF 21,F
00A5: MOVF 21,W
00A6: MOVWF 75
00A7: CALL 05F
00A8: MOVLW 30
00A9: ADDWF 73,F
00AA: MOVF 73,W
00AB: MOVWF 75
00AC: CALL 05F
00AD: RETLW 00
*
02AD: MOVLW 3D
02AE: MOVWF 6B
02AF: MOVLW 4C
02B0: MOVWF 75
02B1: CALL 05F
02B2: MOVLW 3A
02B3: MOVWF 75
02B4: CALL 05F
02B5: MOVLW 20
02B6: MOVWF 75
02B7: CALL 05F
02B8: MOVF 70,W
02B9: MOVWF 73
02BA: MOVLW 18
02BB: MOVWF 74
02BC: CALL 07C
02BD: MOVLW 05
02BE: MOVWF 72
02BF: MOVF 72,W
02C0: CALL 004
02C1: INCF 72,F
02C2: MOVWF 75
02C3: CALL 05F
02C4: MOVLW 0A
02C5: SUBWF 72,W
02C6: BTFSS 03.2
02C7: GOTO 2BF
02C8: MOVF 71,W
02C9: MOVWF 73
02CA: MOVLW 18
02CB: MOVWF 74
02CC: CALL 07C
.................... SendPacket(&AXstring[0]);
02CD: MOVLW 3D
02CE: MOVWF 72
.................... delay_ms(1000);
*
0311: MOVLW 04
0312: MOVWF 72
0313: MOVLW FA
0314: MOVWF 73
0315: CALL 04A
0316: DECFSZ 72,F
0317: GOTO 313
.................... };
0318: GOTO 275
0319: BCF 0A.3
031A: GOTO 45E (RETURN)
.................... }
....................
.................... void cikcak()
.................... {
.................... int n;
.................... switch(movement) // podivej se na jednu stranu
*
0364: MOVLW 01
0365: SUBWF 67,W
0366: ADDLW FD
0367: BTFSC 03.0
0368: GOTO 3A4
0369: ADDLW 03
036A: GOTO 410
.................... {
.................... case L:
.................... FL;BR;
036B: BSF 03.5
036C: BCF 06.7
036D: BCF 03.5
036E: BCF 06.7
036F: BSF 03.5
0370: BCF 06.6
0371: BCF 03.5
0372: BSF 06.6
0373: BSF 03.5
0374: BCF 06.4
0375: BCF 03.5
0376: BCF 06.4
0377: BSF 03.5
0378: BCF 06.5
0379: BCF 03.5
037A: BSF 06.5
.................... movement=R;
037B: MOVLW 01
037C: MOVWF 67
.................... break;
037D: GOTO 3A4
.................... case R:
.................... FR;BL;
037E: BSF 03.5
037F: BCF 06.5
0380: BCF 03.5
0381: BCF 06.5
0382: BSF 03.5
0383: BCF 06.4
0384: BCF 03.5
0385: BSF 06.4
0386: BSF 03.5
0387: BCF 06.6
0388: BCF 03.5
0389: BCF 06.6
038A: BSF 03.5
038B: BCF 06.7
038C: BCF 03.5
038D: BSF 06.7
.................... movement=L;
038E: MOVLW 02
038F: MOVWF 67
.................... break;
0390: GOTO 3A4
.................... case S:
.................... FR;BL;
0391: BSF 03.5
0392: BCF 06.5
0393: BCF 03.5
0394: BCF 06.5
0395: BSF 03.5
0396: BCF 06.4
0397: BCF 03.5
0398: BSF 06.4
0399: BSF 03.5
039A: BCF 06.6
039B: BCF 03.5
039C: BCF 06.6
039D: BSF 03.5
039E: BCF 06.7
039F: BCF 03.5
03A0: BSF 06.7
.................... movement=L;
03A1: MOVLW 02
03A2: MOVWF 67
.................... break;
03A3: GOTO 3A4
.................... }
*
0410: BCF 0A.0
0411: BCF 0A.1
0412: BSF 0A.2
0413: ADDWF 02,F
0414: GOTO 37E
0415: GOTO 36B
0416: GOTO 391
.................... set_adc_channel(LSENSOR);
*
03A4: MOVLW 00
03A5: MOVWF 21
03A6: MOVF 1F,W
03A7: ANDLW C7
03A8: IORWF 21,W
03A9: MOVWF 1F
.................... Delay_us(10);
03AA: MOVLW 03
03AB: MOVWF 20
03AC: DECFSZ 20,F
03AD: GOTO 3AC
.................... while (tresholdL < read_adc()) // je tam cara??
03AE: BSF 1F.2
03AF: BTFSC 1F.2
03B0: GOTO 3AF
03B1: MOVF 1E,W
03B2: SUBWF 65,W
03B3: BTFSC 03.0
03B4: GOTO 3FC
.................... {
.................... if (n==50) // asi bude na druhe strane
03B5: MOVF 6E,W
03B6: SUBLW 32
03B7: BTFSS 03.2
03B8: GOTO 3F7
.................... {
.................... STOPR;STOPL;
03B9: BSF 03.5
03BA: BCF 06.4
03BB: BCF 03.5
03BC: BCF 06.4
03BD: BSF 03.5
03BE: BCF 06.5
03BF: BCF 03.5
03C0: BCF 06.5
03C1: BSF 03.5
03C2: BCF 06.6
03C3: BCF 03.5
03C4: BCF 06.6
03C5: BSF 03.5
03C6: BCF 06.7
03C7: BCF 03.5
03C8: BCF 06.7
.................... n=0;
03C9: CLRF 6E
.................... switch(movement)
03CA: MOVLW 01
03CB: SUBWF 67,W
03CC: ADDLW FE
03CD: BTFSC 03.0
03CE: GOTO 3F7
03CF: ADDLW 02
03D0: GOTO 417
.................... {
.................... case L:
.................... FL;BR;
03D1: BSF 03.5
03D2: BCF 06.7
03D3: BCF 03.5
03D4: BCF 06.7
03D5: BSF 03.5
03D6: BCF 06.6
03D7: BCF 03.5
03D8: BSF 06.6
03D9: BSF 03.5
03DA: BCF 06.4
03DB: BCF 03.5
03DC: BCF 06.4
03DD: BSF 03.5
03DE: BCF 06.5
03DF: BCF 03.5
03E0: BSF 06.5
.................... movement=R;
03E1: MOVLW 01
03E2: MOVWF 67
.................... break;
03E3: GOTO 3F7
.................... case R:
.................... FR;BL;
03E4: BSF 03.5
03E5: BCF 06.5
03E6: BCF 03.5
03E7: BCF 06.5
03E8: BSF 03.5
03E9: BCF 06.4
03EA: BCF 03.5
03EB: BSF 06.4
03EC: BSF 03.5
03ED: BCF 06.6
03EE: BCF 03.5
03EF: BCF 06.6
03F0: BSF 03.5
03F1: BCF 06.7
03F2: BCF 03.5
03F3: BSF 06.7
.................... movement=L;
03F4: MOVLW 02
03F5: MOVWF 67
.................... break;
03F6: GOTO 3F7
.................... }
*
0417: BCF 0A.0
0418: BCF 0A.1
0419: BSF 0A.2
041A: ADDWF 02,F
041B: GOTO 3E4
041C: GOTO 3D1
.................... }
.................... Delay_ms(5);
*
03F7: MOVLW 05
03F8: MOVWF 73
03F9: CALL 04A
.................... n++;
03FA: INCF 6E,F
.................... }
03FB: GOTO 3AE
.................... STOPL;STOPR; // nasli jsme caru
03FC: BSF 03.5
03FD: BCF 06.6
03FE: BCF 03.5
03FF: BCF 06.6
0400: BSF 03.5
0401: BCF 06.7
0402: BCF 03.5
0403: BCF 06.7
0404: BSF 03.5
0405: BCF 06.4
0406: BCF 03.5
0407: BCF 06.4
0408: BSF 03.5
0409: BCF 06.5
040A: BCF 03.5
040B: BCF 06.5
.................... line=S;
040C: MOVLW 03
040D: MOVWF 68
040E: BCF 0A.3
040F: GOTO 610 (RETURN)
.................... }
.................... void objizdka()
.................... {
.................... BL;BR;Delay_ms(300);
*
031B: BSF 03.5
031C: BCF 06.6
031D: BCF 03.5
031E: BCF 06.6
031F: BSF 03.5
0320: BCF 06.7
0321: BCF 03.5
0322: BSF 06.7
0323: BSF 03.5
0324: BCF 06.4
0325: BCF 03.5
0326: BCF 06.4
0327: BSF 03.5
0328: BCF 06.5
0329: BCF 03.5
032A: BSF 06.5
032B: MOVLW 02
032C: MOVWF 6E
032D: MOVLW 96
032E: MOVWF 73
032F: CALL 04A
0330: DECFSZ 6E,F
0331: GOTO 32D
.................... STOPR;STOPL;
0332: BSF 03.5
0333: BCF 06.4
0334: BCF 03.5
0335: BCF 06.4
0336: BSF 03.5
0337: BCF 06.5
0338: BCF 03.5
0339: BCF 06.5
033A: BSF 03.5
033B: BCF 06.6
033C: BCF 03.5
033D: BCF 06.6
033E: BSF 03.5
033F: BCF 06.7
0340: BCF 03.5
0341: BCF 06.7
.................... beep(1000,1000);
0342: MOVLW 03
0343: MOVWF 73
0344: MOVLW E8
0345: MOVWF 72
0346: MOVLW 03
0347: MOVWF 75
0348: MOVLW E8
0349: MOVWF 74
034A: CALL 024
.................... Delay_ms(500);
034B: MOVLW 02
034C: MOVWF 6E
034D: MOVLW FA
034E: MOVWF 73
034F: CALL 04A
0350: DECFSZ 6E,F
0351: GOTO 34D
.................... beep(1000,1000);
0352: MOVLW 03
0353: MOVWF 73
0354: MOVLW E8
0355: MOVWF 72
0356: MOVLW 03
0357: MOVWF 75
0358: MOVLW E8
0359: MOVWF 74
035A: CALL 024
.................... Delay_ms(1000);
035B: MOVLW 04
035C: MOVWF 6E
035D: MOVLW FA
035E: MOVWF 73
035F: CALL 04A
0360: DECFSZ 6E,F
0361: GOTO 35D
0362: BCF 0A.3
0363: GOTO 48A (RETURN)
....................
.................... }
.................... void kalibrace()
.................... {
.................... unsigned int16 i;
.................... int min;
.................... int max;
.................... int current;
.................... int treshold;
....................
.................... FL; BR; Delay_ms(130);
.................... chyba1:
.................... FR; BL; //kalibrace leveho cidla
.................... set_adc_channel(LSENSOR);
.................... Delay_us(20);
.................... min=max=read_adc();
.................... for (i=1;i<=500;i++)
.................... {
.................... current=read_adc();
.................... if (max < current) max=current;
.................... if (min > current) min=current;
.................... Delay_us(500);
.................... }
.................... FL; BR;
.................... for (i=1;i<=500;i++)
.................... {
.................... current=read_adc();
.................... if (max < current) max=current;
.................... if (min > current) min=current;
.................... Delay_us(500);
.................... }
.................... STOPL; STOPR; Delay_ms(200);
.................... if((max-min)<50) {Beep(1000,300); GOTO chyba1;}
.................... treshold=(max-min)>>1;
.................... tresholdL=treshold+min;
....................
.................... chyba2:
.................... FR; BL;
.................... set_adc_channel(RSENSOR);
.................... Delay_us(20);
.................... min=max=read_adc(); //naplneni min a max nejakou rozumnou hodnotou
.................... for (i=1;i<=500 ;i++)
.................... {
.................... current=read_adc();
.................... if (max < current) max=current; //zmereni minima a maxima
.................... if (min > current) min=current;
.................... Delay_us(500);
.................... }
.................... FL; BR;
.................... for (i=1;i<=500 ;i++)
.................... {
.................... current=read_adc();
.................... if (max < current) max=current; //zmereni minima a maxima
.................... if (min > current) min=current;
.................... Delay_us(500);
.................... }
.................... STOPL; STOPR; Delay_ms(200);
.................... if((max-min)<50) {Beep(1000,300); GOTO chyba2;}
.................... treshold=(max-min)>>1;
.................... tresholdR=treshold+min;
....................
.................... FR; BL;
.................... movement=L;
.................... set_adc_channel(LSENSOR);
.................... Delay_us(20);
.................... while (tresholdL < read_adc()) Delay_us(100);
.................... FL; BR; Delay_ms(50);
.................... STOPL; STOPR; Delay_ms(500);
.................... Beep(780,200);
.................... }
....................
.................... void main()
.................... {
.................... unsigned int16 rovne; // pocita delku rovne cary
*
041D: CLRF 04
041E: MOVLW 1F
041F: ANDWF 03,F
0420: MOVLW 07
0421: BSF 03.5
0422: MOVWF 1F
0423: MOVLW 82
0424: BCF 03.5
0425: MOVWF 25
0426: MOVLW 98
0427: MOVWF 26
0428: MOVWF 27
0429: MOVLW 40
042A: MOVWF 28
042B: MOVWF 29
042C: MOVWF 2A
042D: MOVLW 60
042E: MOVWF 2B
042F: MOVLW 86
0430: MOVWF 2C
0431: MOVLW B4
0432: MOVWF 2D
0433: MOVLW 60
0434: MOVWF 2E
0435: MOVLW A4
0436: MOVWF 2F
0437: MOVWF 30
0438: MOVWF 31
0439: MOVLW 61
043A: MOVWF 32
043B: MOVLW 03
043C: MOVWF 33
043D: MOVLW F0
043E: MOVWF 34
043F: MOVLW FF
0440: MOVWF 3C
0441: CLRF 6B
....................
.................... STOPL; STOPR;
0442: BSF 03.5
0443: BCF 06.6
0444: BCF 03.5
0445: BCF 06.6
0446: BSF 03.5
0447: BCF 06.7
0448: BCF 03.5
0449: BCF 06.7
044A: BSF 03.5
044B: BCF 06.4
044C: BCF 03.5
044D: BCF 06.4
044E: BSF 03.5
044F: BCF 06.5
0450: BCF 03.5
0451: BCF 06.5
....................
.................... setup_adc_ports(RA0_RA1_RA3_ANALOG);
0452: MOVLW 04
0453: BSF 03.5
0454: MOVWF 1F
.................... setup_adc(ADC_CLOCK_DIV_2);
0455: BCF 03.5
0456: MOVF 1F,W
0457: ANDLW 38
0458: IORLW 01
0459: MOVWF 1F
....................
.................... port_b_pullups(false);
045A: BSF 03.5
045B: BSF 01.7
....................
.................... diagnostika();
045C: BCF 03.5
045D: GOTO 14A
....................
.................... Beep(1000,200); //double beep
045E: MOVLW 03
045F: MOVWF 73
0460: MOVLW E8
0461: MOVWF 72
0462: CLRF 75
0463: MOVLW C8
0464: MOVWF 74
0465: CALL 024
.................... Delay_ms(50);
0466: MOVLW 32
0467: MOVWF 73
0468: CALL 04A
.................... Beep(1000,200);
0469: MOVLW 03
046A: MOVWF 73
046B: MOVLW E8
046C: MOVWF 72
046D: CLRF 75
046E: MOVLW C8
046F: MOVWF 74
0470: CALL 024
.................... Delay_ms(1000); // 1s
0471: MOVLW 04
0472: MOVWF 6E
0473: MOVLW FA
0474: MOVWF 73
0475: CALL 04A
0476: DECFSZ 6E,F
0477: GOTO 473
....................
.................... // kalibrace();
.................... tresholdl=tresholdr=80;
0478: MOVLW 50
0479: MOVWF 66
047A: MOVWF 65
.................... // FL; FR;
.................... movement=S;
047B: MOVLW 03
047C: MOVWF 67
.................... line=S;
047D: MOVWF 68
.................... dira=0;
047E: CLRF 6A
047F: CLRF 69
.................... rovne=0;
0480: CLRF 6D
0481: CLRF 6C
....................
.................... while(true)
.................... {
.................... if(!input(BUMPER)) objizdka();
0482: BSF 3C.4
0483: MOVF 3C,W
0484: BSF 03.5
0485: MOVWF 07
0486: BCF 03.5
0487: BTFSC 07.4
0488: GOTO 48A
0489: GOTO 31B
.................... line=0;
048A: CLRF 68
.................... set_adc_channel(RSENSOR); // podivej se jestli neni cara pod pravym cidlem
048B: MOVLW 08
048C: MOVWF 21
048D: MOVF 1F,W
048E: ANDLW C7
048F: IORWF 21,W
0490: MOVWF 1F
.................... Delay_us(10);
0491: MOVLW 03
0492: MOVWF 20
0493: DECFSZ 20,F
0494: GOTO 493
.................... if(tresholdR > read_adc())
0495: BSF 1F.2
0496: BTFSC 1F.2
0497: GOTO 496
0498: MOVF 1E,W
0499: SUBWF 66,W
049A: BTFSC 03.2
049B: GOTO 4A2
049C: BTFSS 03.0
049D: GOTO 4A2
.................... {
.................... dira=0;
049E: CLRF 6A
049F: CLRF 69
.................... line=R;
04A0: MOVLW 01
04A1: MOVWF 68
.................... }
.................... set_adc_channel(LSENSOR); // kdyz cara nebyla pod pravym cidlem, mozna bude pod levym
04A2: MOVLW 00
04A3: MOVWF 21
04A4: MOVF 1F,W
04A5: ANDLW C7
04A6: IORWF 21,W
04A7: MOVWF 1F
.................... Delay_us(10);
04A8: MOVLW 03
04A9: MOVWF 20
04AA: DECFSZ 20,F
04AB: GOTO 4AA
.................... if(tresholdL > read_adc())
04AC: BSF 1F.2
04AD: BTFSC 1F.2
04AE: GOTO 4AD
04AF: MOVF 1E,W
04B0: SUBWF 65,W
04B1: BTFSC 03.2
04B2: GOTO 4B8
04B3: BTFSS 03.0
04B4: GOTO 4B8
.................... {
.................... dira=0;
04B5: CLRF 6A
04B6: CLRF 69
.................... line=line | L;
04B7: BSF 68.1
.................... }
....................
.................... switch(line)
04B8: MOVF 68,W
04B9: MOVWF 20
04BA: MOVLW 03
04BB: SUBWF 20,W
04BC: BTFSC 03.2
04BD: GOTO 4C7
04BE: MOVLW 02
04BF: SUBWF 20,W
04C0: BTFSC 03.2
04C1: GOTO 4DA
04C2: MOVLW 01
04C3: SUBWF 20,W
04C4: BTFSC 03.2
04C5: GOTO 4ED
04C6: GOTO 500
.................... {
.................... case S:
.................... FR;FL;
04C7: BSF 03.5
04C8: BCF 06.5
04C9: BCF 03.5
04CA: BCF 06.5
04CB: BSF 03.5
04CC: BCF 06.4
04CD: BCF 03.5
04CE: BSF 06.4
04CF: BSF 03.5
04D0: BCF 06.7
04D1: BCF 03.5
04D2: BCF 06.7
04D3: BSF 03.5
04D4: BCF 06.6
04D5: BCF 03.5
04D6: BSF 06.6
.................... movement=S;
04D7: MOVLW 03
04D8: MOVWF 67
.................... continue;
04D9: GOTO 482
.................... case L:
.................... STOPL;
04DA: BSF 03.5
04DB: BCF 06.6
04DC: BCF 03.5
04DD: BCF 06.6
04DE: BSF 03.5
04DF: BCF 06.7
04E0: BCF 03.5
04E1: BCF 06.7
.................... FR;movement=L;
04E2: BSF 03.5
04E3: BCF 06.5
04E4: BCF 03.5
04E5: BCF 06.5
04E6: BSF 03.5
04E7: BCF 06.4
04E8: BCF 03.5
04E9: BSF 06.4
04EA: MOVLW 02
04EB: MOVWF 67
.................... continue;
04EC: GOTO 482
.................... case R:
.................... STOPR;
04ED: BSF 03.5
04EE: BCF 06.4
04EF: BCF 03.5
04F0: BCF 06.4
04F1: BSF 03.5
04F2: BCF 06.5
04F3: BCF 03.5
04F4: BCF 06.5
.................... FL;movement=R;
04F5: BSF 03.5
04F6: BCF 06.7
04F7: BCF 03.5
04F8: BCF 06.7
04F9: BSF 03.5
04FA: BCF 06.6
04FB: BCF 03.5
04FC: BSF 06.6
04FD: MOVLW 01
04FE: MOVWF 67
.................... continue;
04FF: GOTO 482
.................... default:
.................... }
....................
.................... if (dira==ODEZVA) // kdyz uz chvili jedeme po bile plose
0500: DECFSZ 69,W
0501: GOTO 54A
0502: MOVF 6A,F
0503: BTFSS 03.2
0504: GOTO 54A
.................... {
.................... //BR;BL;Delay_us(rovne >>= 5);
.................... rovne=0; //kdyz sme museli zatocit, uz neni rovna cara
0505: CLRF 6D
0506: CLRF 6C
....................
.................... switch (line) // musime zatocit
0507: MOVLW 01
0508: SUBWF 68,W
0509: ADDLW FE
050A: BTFSC 03.0
050B: GOTO 54A
050C: ADDLW 02
050D: GOTO 617
.................... {
.................... case L:
.................... BL;Delay_ms(BRZDENI);STOPL;
050E: BSF 03.5
050F: BCF 06.6
0510: BCF 03.5
0511: BCF 06.6
0512: BSF 03.5
0513: BCF 06.7
0514: BCF 03.5
0515: BSF 06.7
0516: MOVLW 64
0517: MOVWF 73
0518: CALL 04A
0519: BSF 03.5
051A: BCF 06.6
051B: BCF 03.5
051C: BCF 06.6
051D: BSF 03.5
051E: BCF 06.7
051F: BCF 03.5
0520: BCF 06.7
.................... FR;
0521: BSF 03.5
0522: BCF 06.5
0523: BCF 03.5
0524: BCF 06.5
0525: BSF 03.5
0526: BCF 06.4
0527: BCF 03.5
0528: BSF 06.4
.................... movement=L;
0529: MOVLW 02
052A: MOVWF 67
.................... break;
052B: GOTO 54A
.................... case R:
.................... BR;Delay_ms(BRZDENI);STOPR;
052C: BSF 03.5
052D: BCF 06.4
052E: BCF 03.5
052F: BCF 06.4
0530: BSF 03.5
0531: BCF 06.5
0532: BCF 03.5
0533: BSF 06.5
0534: MOVLW 64
0535: MOVWF 73
0536: CALL 04A
0537: BSF 03.5
0538: BCF 06.4
0539: BCF 03.5
053A: BCF 06.4
053B: BSF 03.5
053C: BCF 06.5
053D: BCF 03.5
053E: BCF 06.5
.................... FL;
053F: BSF 03.5
0540: BCF 06.7
0541: BCF 03.5
0542: BCF 06.7
0543: BSF 03.5
0544: BCF 06.6
0545: BCF 03.5
0546: BSF 06.6
.................... movement=R;
0547: MOVLW 01
0548: MOVWF 67
.................... break;
0549: GOTO 54A
.................... }
*
0617: BCF 0A.0
0618: BSF 0A.1
0619: BSF 0A.2
061A: ADDWF 02,F
061B: GOTO 52C
061C: GOTO 50E
.................... }
.................... if (dira==MEZERA) // kdyz zkoncila cara
*
054A: MOVF 69,W
054B: SUBLW 18
054C: BTFSS 03.2
054D: GOTO 612
054E: MOVF 6A,W
054F: SUBLW 15
0550: BTFSS 03.2
0551: GOTO 612
.................... {
.................... beep(800,500);
0552: MOVLW 03
0553: MOVWF 73
0554: MOVLW 20
0555: MOVWF 72
0556: MOVLW 01
0557: MOVWF 75
0558: MOVLW F4
0559: MOVWF 74
055A: CALL 024
.................... Delay_ms(50);
055B: MOVLW 32
055C: MOVWF 73
055D: CALL 04A
.................... beep(800,500);
055E: MOVLW 03
055F: MOVWF 73
0560: MOVLW 20
0561: MOVWF 72
0562: MOVLW 01
0563: MOVWF 75
0564: MOVLW F4
0565: MOVWF 74
0566: CALL 024
.................... switch (movement) //vrat se zpet na caru
0567: MOVLW 01
0568: SUBWF 67,W
0569: ADDLW FD
056A: BTFSC 03.0
056B: GOTO 5E6
056C: ADDLW 03
056D: GOTO 61D
.................... {
.................... case L:
.................... STOPL;STOPR;
056E: BSF 03.5
056F: BCF 06.6
0570: BCF 03.5
0571: BCF 06.6
0572: BSF 03.5
0573: BCF 06.7
0574: BCF 03.5
0575: BCF 06.7
0576: BSF 03.5
0577: BCF 06.4
0578: BCF 03.5
0579: BCF 06.4
057A: BSF 03.5
057B: BCF 06.5
057C: BCF 03.5
057D: BCF 06.5
.................... BR;Delay_ms(COUVANI);STOPR;
057E: BSF 03.5
057F: BCF 06.4
0580: BCF 03.5
0581: BCF 06.4
0582: BSF 03.5
0583: BCF 06.5
0584: BCF 03.5
0585: BSF 06.5
0586: MOVLW 08
0587: MOVWF 6E
0588: MOVLW C8
0589: MOVWF 73
058A: CALL 04A
058B: DECFSZ 6E,F
058C: GOTO 588
058D: BSF 03.5
058E: BCF 06.4
058F: BCF 03.5
0590: BCF 06.4
0591: BSF 03.5
0592: BCF 06.5
0593: BCF 03.5
0594: BCF 06.5
.................... break;
0595: GOTO 5E6
.................... case R:
.................... STOPL;STOPR;
0596: BSF 03.5
0597: BCF 06.6
0598: BCF 03.5
0599: BCF 06.6
059A: BSF 03.5
059B: BCF 06.7
059C: BCF 03.5
059D: BCF 06.7
059E: BSF 03.5
059F: BCF 06.4
05A0: BCF 03.5
05A1: BCF 06.4
05A2: BSF 03.5
05A3: BCF 06.5
05A4: BCF 03.5
05A5: BCF 06.5
.................... BL;Delay_ms(COUVANI);STOPL;
05A6: BSF 03.5
05A7: BCF 06.6
05A8: BCF 03.5
05A9: BCF 06.6
05AA: BSF 03.5
05AB: BCF 06.7
05AC: BCF 03.5
05AD: BSF 06.7
05AE: MOVLW 08
05AF: MOVWF 6E
05B0: MOVLW C8
05B1: MOVWF 73
05B2: CALL 04A
05B3: DECFSZ 6E,F
05B4: GOTO 5B0
05B5: BSF 03.5
05B6: BCF 06.6
05B7: BCF 03.5
05B8: BCF 06.6
05B9: BSF 03.5
05BA: BCF 06.7
05BB: BCF 03.5
05BC: BCF 06.7
.................... break;
05BD: GOTO 5E6
.................... case S:
.................... BL; BR; Delay_ms(COUVANI);
05BE: BSF 03.5
05BF: BCF 06.6
05C0: BCF 03.5
05C1: BCF 06.6
05C2: BSF 03.5
05C3: BCF 06.7
05C4: BCF 03.5
05C5: BSF 06.7
05C6: BSF 03.5
05C7: BCF 06.4
05C8: BCF 03.5
05C9: BCF 06.4
05CA: BSF 03.5
05CB: BCF 06.5
05CC: BCF 03.5
05CD: BSF 06.5
05CE: MOVLW 08
05CF: MOVWF 6E
05D0: MOVLW C8
05D1: MOVWF 73
05D2: CALL 04A
05D3: DECFSZ 6E,F
05D4: GOTO 5D0
.................... STOPL; STOPR;
05D5: BSF 03.5
05D6: BCF 06.6
05D7: BCF 03.5
05D8: BCF 06.6
05D9: BSF 03.5
05DA: BCF 06.7
05DB: BCF 03.5
05DC: BCF 06.7
05DD: BSF 03.5
05DE: BCF 06.4
05DF: BCF 03.5
05E0: BCF 06.4
05E1: BSF 03.5
05E2: BCF 06.5
05E3: BCF 03.5
05E4: BCF 06.5
.................... break;
05E5: GOTO 5E6
.................... }
*
061D: BCF 0A.0
061E: BSF 0A.1
061F: BSF 0A.2
0620: ADDWF 02,F
0621: GOTO 596
0622: GOTO 56E
0623: GOTO 5BE
....................
.................... FR;FL; Delay_ms(PRES_DIRU); // popojedem dopredu mozna tam bude cara
*
05E6: BSF 03.5
05E7: BCF 06.5
05E8: BCF 03.5
05E9: BCF 06.5
05EA: BSF 03.5
05EB: BCF 06.4
05EC: BCF 03.5
05ED: BSF 06.4
05EE: BSF 03.5
05EF: BCF 06.7
05F0: BCF 03.5
05F1: BCF 06.7
05F2: BSF 03.5
05F3: BCF 06.6
05F4: BCF 03.5
05F5: BSF 06.6
05F6: MOVLW 02
05F7: MOVWF 6E
05F8: MOVLW C8
05F9: MOVWF 73
05FA: CALL 04A
05FB: DECFSZ 6E,F
05FC: GOTO 5F8
.................... STOPL; STOPR; movement=S;
05FD: BSF 03.5
05FE: BCF 06.6
05FF: BCF 03.5
0600: BCF 06.6
0601: BSF 03.5
0602: BCF 06.7
0603: BCF 03.5
0604: BCF 06.7
0605: BSF 03.5
0606: BCF 06.4
0607: BCF 03.5
0608: BCF 06.4
0609: BSF 03.5
060A: BCF 06.5
060B: BCF 03.5
060C: BCF 06.5
060D: MOVLW 03
060E: MOVWF 67
.................... cikcak(); // najdi caru
060F: GOTO 364
.................... dira=0;
0610: CLRF 6A
0611: CLRF 69
.................... }
.................... dira++;
0612: INCF 69,F
0613: BTFSC 03.2
0614: INCF 6A,F
.................... } // while(true)
0615: GOTO 482
.................... }
....................
0616: SLEEP
/roboti/istrobot/merkur/PIC16F873/main.SYM
0,0 → 1,89
003 STATUS
015-016 CCP_1
015 CCP_1_LOW
016 CCP_1_HIGH
01B-01C CCP_2
01B CCP_2_LOW
01C CCP_2_HIGH
020 @SCRATCH
021 @SCRATCH
021 _RETURN_
022 @SCRATCH
023 @SCRATCH
024 @SCRATCH
025-034 SendData
035.0 bit
036 fcslo
037 fcshi
038 stuff
039 flag_flag
03A fcs_flag
03B i
03C @TRIS_C
03D-064 AXstring
065 tresholdL
066 tresholdR
067 movement
068 line
069-06A dira
06B @sprintf_string
06C-06D main.rovne
06E-06F diagnostika.n
06E cikcak.n
06E objizdka.@SCRATCH
06E main.@SCRATCH
070 ls
071 rs
072 SendPacket.data
072-073 beep.period
072 diagnostika.@SCRATCH
073 delay_ms.P1
073 @PRINTF_U_290.P2
073 SendPacket.@SCRATCH
074 SendByte.inbyte
074-075 beep.length
074 @PRINTF_U_290.P1
075 SendByte.k
075 @SPRINTF.P1
075 @DIV88.P2
076 SendByte.bt
076-077 beep.nn
076 @DIV88.P1
077 fcsbit.tbyte
077 SendByte.@SCRATCH
077 @DIV88.@SCRATCH
078 delay_us.P1
078 fcsbit.@SCRATCH
079 fcsbit.@SCRATCH
-000 kalibrace.i
kalibrace.min
kalibrace.max
kalibrace.current
kalibrace.treshold
 
004A delay_ms
0016 delay_us
00AE flipout
00B5 SendBit
00FF SendByte
0024 beep
014A diagnostika
0004 @const10170
005F @SPRINTF
0067 @DIV88
007C @PRINTF_U_290
0364 cikcak
0410 @goto10199
0417 @goto10214
031B objizdka
041D main
0617 @goto10341
061D @goto10355
0135 chyba1
0135 chyba2
 
Project Files:
d:\kaklik\programy\pic_c\roboti\merkur\main.c
d:\kaklik\programy\pic_c\roboti\merkur\main.h
C:\Program Files\PICC\devices\16F873.h
C:\library\kaklik\CCS\AX25.c
/roboti/istrobot/merkur/PIC16F873/main.c
0,0 → 1,332
#include "main.h"
 
#define TXo PIN_C3 // To the transmitter modulator
#include "AX25.c" // podprogram pro prenos telemetrie
 
//motory //Napred vypnout potom zapnout!
#define FR output_low(PIN_B5); output_high(PIN_B4) // Vpred
#define FL output_low(PIN_B7); output_high(PIN_B6)
#define BR output_low(PIN_B4); output_high(PIN_B5) // Vzad
#define BL output_low(PIN_B6); output_high(PIN_B7)
#define STOPR output_low(PIN_B4);output_low(PIN_B5)
#define STOPL output_low(PIN_B6);output_low(PIN_B7)
 
#define L 0b10 // left
#define R 0b01 // right
#define S 0b11 // straight
 
#define COUVANI 1600 // couvnuti po zjisteni diry
#define MEZERA 5400 // za jak dlouho bude ztracena cara
#define PRES_DIRU 400 // velikost mezery v care
#define ODEZVA 1 // za jak dlouho po opusteni cary se ma zacit zatacet
#define BRZDENI 100 // doba (v ms) ptrebna k zastaveni jednoho motoru
 
//cidla
#define RSENSOR 1 // Senzory na caru
#define LSENSOR 0
#define BUMPER PIN_C4 // sensor na cihlu
 
#define DIAG_SERVO PIN_B0 // Propojka pro diagnosticky mod
#define DIAG_SENSORS PIN_B1 // Propojka pro diagnosticky mod
 
#DEFINE SOUND_HI PIN_B3
#DEFINE SOUND_LO PIN_B2
 
char AXstring[40]; // Buffer pro prenos telemetrie
 
int tresholdL; // rozhodovaci uroven pro prave cidlo
int tresholdR; // rozhodovaci uroven pro prave cidlo
int movement; // smer minuleho pohybu
int line; // na ktere strane byla detekovana cara
unsigned int16 dira; // pocitadlo pro nalezeni preruseni cary
 
// Primitivni Pipani
void beep(unsigned int16 period, unsigned int16 length)
{
unsigned int16 nn;
 
for(nn=length; nn>0; nn--)
{
output_high(SOUND_HI);output_low(SOUND_LO);
delay_us(period);
output_high(SOUND_LO);output_low(SOUND_HI);
delay_us(period);
}
}
 
// Diagnostika pohonu, hejbne vsema motorama ve vsech smerech
void diagnostika()
{
unsigned int16 n;
 
while (input(DIAG_SERVO)) // Propojka, ktera spousti diagnostiku
{
for (n=500; n<800; n+=100)
{
beep(n,n); //beep UP
};
Delay_ms(1000);
//zastav vse
STOPL; STOPR;
//pravy pas
FR; Delay_ms(1000); STOPR; Delay_ms(1000);
BR; Delay_ms(1000); STOPR; Delay_ms(1000);
Beep(880,100); Delay_ms(1000);
//levy pas
FL; Delay_ms(1000); STOPL; Delay_ms(1000);
BL; Delay_ms(1000); STOPL; Delay_ms(1000);
Beep(880,100); Delay_ms(1000);
//oba pasy
FL; FR; Delay_ms(1000); STOPL; STOPR; Delay_ms(1000);
BL; BR; Delay_ms(1000); STOPL; STOPR; Delay_ms(1000);
};
 
while (input(DIAG_SENSORS))
{
int ls, rs;
while(!input(BUMPER)){beep(1100,100); Delay_ms(50);}
set_adc_channel(RSENSOR);
Delay_us(20);
rs=read_adc();
set_adc_channel(LSENSOR);
Delay_us(20);
ls=read_adc();
sprintf(AXstring,"L: %U R: %U\0", ls, rs); // Convert DATA to String.
SendPacket(&AXstring[0]);
delay_ms(1000);
};
}
 
void cikcak()
{
int n;
switch(movement) // podivej se na jednu stranu
{
case L:
FL;BR;
movement=R;
break;
case R:
FR;BL;
movement=L;
break;
case S:
FR;BL;
movement=L;
break;
}
set_adc_channel(LSENSOR);
Delay_us(10);
while (tresholdL < read_adc()) // je tam cara?
{
if (n==50) // asi bude na druhe strane
{
STOPR;STOPL;
n=0;
switch(movement)
{
case L:
FL;BR;
movement=R;
break;
case R:
FR;BL;
movement=L;
break;
}
}
Delay_ms(5);
n++;
}
STOPL;STOPR; // nasli jsme caru
line=S;
}
void objizdka()
{
BL;BR;Delay_ms(300);
STOPR;STOPL;
beep(1000,1000);
Delay_ms(500);
beep(1000,1000);
Delay_ms(1000);
 
}
void kalibrace()
{
unsigned int16 i;
int min;
int max;
int current;
int treshold;
 
FL; BR; Delay_ms(130);
chyba1:
FR; BL; //kalibrace leveho cidla
set_adc_channel(LSENSOR);
Delay_us(20);
min=max=read_adc();
for (i=1;i<=500;i++)
{
current=read_adc();
if (max < current) max=current;
if (min > current) min=current;
Delay_us(500);
}
FL; BR;
for (i=1;i<=500;i++)
{
current=read_adc();
if (max < current) max=current;
if (min > current) min=current;
Delay_us(500);
}
STOPL; STOPR; Delay_ms(200);
if((max-min)<50) {Beep(1000,300); GOTO chyba1;}
treshold=(max-min)>>1;
tresholdL=treshold+min;
 
chyba2:
FR; BL;
set_adc_channel(RSENSOR);
Delay_us(20);
min=max=read_adc(); //naplneni min a max nejakou rozumnou hodnotou
for (i=1;i<=500 ;i++)
{
current=read_adc();
if (max < current) max=current; //zmereni minima a maxima
if (min > current) min=current;
Delay_us(500);
}
FL; BR;
for (i=1;i<=500 ;i++)
{
current=read_adc();
if (max < current) max=current; //zmereni minima a maxima
if (min > current) min=current;
Delay_us(500);
}
STOPL; STOPR; Delay_ms(200);
if((max-min)<50) {Beep(1000,300); GOTO chyba2;}
treshold=(max-min)>>1;
tresholdR=treshold+min;
 
FR; BL;
movement=L;
set_adc_channel(LSENSOR);
Delay_us(20);
while (tresholdL < read_adc()) Delay_us(100);
FL; BR; Delay_ms(50);
STOPL; STOPR; Delay_ms(500);
Beep(780,200);
}
 
void main()
{
unsigned int16 rovne; // pocita delku rovne cary
 
STOPL; STOPR;
 
setup_adc_ports(RA0_RA1_RA3_ANALOG);
setup_adc(ADC_CLOCK_DIV_2);
 
port_b_pullups(false);
 
diagnostika();
 
Beep(1000,200); //double beep
Delay_ms(50);
Beep(1000,200);
Delay_ms(1000); // 1s
 
// kalibrace();
tresholdl=tresholdr=80;
// FL; FR;
movement=S;
line=S;
dira=0;
rovne=0;
 
while(true)
{
if(!input(BUMPER)) objizdka();
line=0;
set_adc_channel(RSENSOR); // podivej se jestli neni cara pod pravym cidlem
Delay_us(10);
if(tresholdR > read_adc())
{
dira=0;
line=R;
}
set_adc_channel(LSENSOR); // kdyz cara nebyla pod pravym cidlem, mozna bude pod levym
Delay_us(10);
if(tresholdL > read_adc())
{
dira=0;
line=line | L;
}
 
switch(line)
{
case S:
FR;FL;
movement=S;
continue;
case L:
STOPL;
FR;movement=L;
continue;
case R:
STOPR;
FL;movement=R;
continue;
default:
}
 
if (dira==ODEZVA) // kdyz uz chvili jedeme po bile plose
{
//BR;BL;Delay_us(rovne >>= 5);
rovne=0; //kdyz sme museli zatocit, uz neni rovna cara
 
switch (line) // musime zatocit
{
case L:
BL;Delay_ms(BRZDENI);STOPL;
FR;
movement=L;
break;
case R:
BR;Delay_ms(BRZDENI);STOPR;
FL;
movement=R;
break;
}
}
if (dira==MEZERA) // kdyz zkoncila cara
{
beep(800,500);
Delay_ms(50);
beep(800,500);
switch (movement) //vrat se zpet na caru
{
case L:
STOPL;STOPR;
BR;Delay_ms(COUVANI);STOPR;
break;
case R:
STOPL;STOPR;
BL;Delay_ms(COUVANI);STOPL;
break;
case S:
BL; BR; Delay_ms(COUVANI);
STOPL; STOPR;
break;
}
 
FR;FL; Delay_ms(PRES_DIRU); // popojedem dopredu mozna tam bude cara
STOPL; STOPR; movement=S;
cikcak(); // najdi caru
dira=0;
}
dira++;
} // while(true)
}
/roboti/istrobot/merkur/PIC16F873/main.cod
Cannot display: file marked as a binary type.
svn:mime-type = application/octet-stream
Property changes:
Added: svn:mime-type
+application/octet-stream
\ No newline at end of property
/roboti/istrobot/merkur/PIC16F873/main.err
0,0 → 1,0
No Errors
/roboti/istrobot/merkur/PIC16F873/main.h
0,0 → 1,5
#include <16F873.h>
#device adc=8
#use delay(clock=4000000)
#fuses XT,NOWDT,NOLVP
 
/roboti/istrobot/merkur/PIC16F873/main.pjt
0,0 → 1,40
[PROJECT]
Target=main.HEX
Development_Mode=
Processor=0x873F
ToolSuite=CCS
 
[Directories]
Include=C:\Program Files\PICC\devices\;C:\Program Files\PICC\drivers\;C:\library\CCS;
Library=
LinkerScript=
 
[Target Data]
FileList=main.c;
BuildTool=C-COMPILER
OptionString=+FM
AdditionalOptionString=
BuildRequired=1
 
[main.c]
Type=4
Path=
FileList=
BuildTool=
OptionString=
AdditionalOptionString=
 
[mru-list]
1=main.c
 
[Windows]
0=0000 main.c 0 0 796 451 3 0
 
[Opened Files]
1=D:\KAKL\PIC\Tank\main.c
2=D:\KAKL\PIC\Tank\main.h
3=D:\KAKL\PIC\Tank\AX25.c
4=C:\Program Files\PICC\devices\16F88.h
5=
6=
7=
/roboti/istrobot/merkur/PIC16F873/main.sta
0,0 → 1,46
 
ROM used: 1572 (38%)
2048 (50%) including unused fragments
 
2 Average locations per line
4 Average locations per statement
 
RAM used: 79 (41%) at main() level
90 (47%) worst case
 
Lines Stmts % Files
----- ----- --- -----
333 374 85 d:\kaklik\programy\pic_c\roboti\merkur\main.c
6 0 0 d:\kaklik\programy\pic_c\roboti\merkur\main.h
225 0 0 C:\Program Files\PICC\devices\16F873.h
136 67 8 C:\library\kaklik\CCS\AX25.c
----- -----
1400 882 Total
 
Page ROM % RAM Functions:
---- --- --- --- ----------
0 21 1 1 delay_ms
0 14 1 1 delay_us
0 7 0 0 flipout
0 74 5 0 SendBit
0 75 5 4 SendByte
0 38 2 6 beep
0 465 30 3 diagnostika
0 18 1 0 @const10170
0 8 1 1 @SPRINTF
0 21 1 3 @DIV88
0 50 3 2 @PRINTF_U_290
0 172 11 1 cikcak
0 7 0 0 @goto10199
0 6 0 0 @goto10214
0 73 5 1 objizdka
0 506 32 3 main
0 6 0 0 @goto10341
0 7 0 0 @goto10355
 
Segment Used Free
--------- ---- ----
0000-0003 4 0
0004-07FF 1568 476
0800-0FFF 0 2048
 
/roboti/istrobot/merkur/PIC16F873/main.tre
0,0 → 1,124
ÀÄmain
ÀÄmain 0/506 Ram=3
ÃÄ??0??
ÃÄdiagnostika 0/465 Ram=3
³ ÃÄbeep 0/38 Ram=6
³ ³ ÃÄdelay_us 0/14 Ram=1
³ ³ ÀÄdelay_us 0/14 Ram=1
³ ÃÄdelay_ms 0/21 Ram=1
³ ÃÄdelay_ms 0/21 Ram=1
³ ÃÄdelay_ms 0/21 Ram=1
³ ÃÄdelay_ms 0/21 Ram=1
³ ÃÄdelay_ms 0/21 Ram=1
³ ÃÄbeep 0/38 Ram=6
³ ³ ÃÄdelay_us 0/14 Ram=1
³ ³ ÀÄdelay_us 0/14 Ram=1
³ ÃÄdelay_ms 0/21 Ram=1
³ ÃÄdelay_ms 0/21 Ram=1
³ ÃÄdelay_ms 0/21 Ram=1
³ ÃÄdelay_ms 0/21 Ram=1
³ ÃÄdelay_ms 0/21 Ram=1
³ ÃÄbeep 0/38 Ram=6
³ ³ ÃÄdelay_us 0/14 Ram=1
³ ³ ÀÄdelay_us 0/14 Ram=1
³ ÃÄdelay_ms 0/21 Ram=1
³ ÃÄdelay_ms 0/21 Ram=1
³ ÃÄdelay_ms 0/21 Ram=1
³ ÃÄdelay_ms 0/21 Ram=1
³ ÃÄdelay_ms 0/21 Ram=1
³ ÃÄbeep 0/38 Ram=6
³ ³ ÃÄdelay_us 0/14 Ram=1
³ ³ ÀÄdelay_us 0/14 Ram=1
³ ÃÄdelay_ms 0/21 Ram=1
³ ÃÄ@SPRINTF 0/8 Ram=1
³ ÃÄ@SPRINTF 0/8 Ram=1
³ ÃÄ@SPRINTF 0/8 Ram=1
³ ÃÄ@PRINTF_U_290 0/50 Ram=2
³ ³ ÃÄ@DIV88 0/21 Ram=3
³ ³ ÃÄ@SPRINTF 0/8 Ram=1
³ ³ ÃÄ@DIV88 0/21 Ram=3
³ ³ ÃÄ@SPRINTF 0/8 Ram=1
³ ³ ÀÄ@SPRINTF 0/8 Ram=1
³ ÃÄ@const10170 0/18 Ram=0
³ ÃÄ@SPRINTF 0/8 Ram=1
³ ÃÄ@PRINTF_U_290 0/50 Ram=2
³ ³ ÃÄ@DIV88 0/21 Ram=3
³ ³ ÃÄ@SPRINTF 0/8 Ram=1
³ ³ ÃÄ@DIV88 0/21 Ram=3
³ ³ ÃÄ@SPRINTF 0/8 Ram=1
³ ³ ÀÄ@SPRINTF 0/8 Ram=1
³ ÃÄSendPacket (Inline) Ram=2
³ ³ ÃÄSendByte 0/75 Ram=4
³ ³ ³ ÃÄfcsbit (Inline) Ram=3
³ ³ ³ ÃÄflipout 0/7 Ram=0
³ ³ ³ ÃÄSendBit 0/74 Ram=0
³ ³ ³ ÃÄflipout 0/7 Ram=0
³ ³ ³ ÀÄSendBit 0/74 Ram=0
³ ³ ÃÄSendByte 0/75 Ram=4
³ ³ ³ ÃÄfcsbit (Inline) Ram=3
³ ³ ³ ÃÄflipout 0/7 Ram=0
³ ³ ³ ÃÄSendBit 0/74 Ram=0
³ ³ ³ ÃÄflipout 0/7 Ram=0
³ ³ ³ ÀÄSendBit 0/74 Ram=0
³ ³ ÃÄSendByte 0/75 Ram=4
³ ³ ³ ÃÄfcsbit (Inline) Ram=3
³ ³ ³ ÃÄflipout 0/7 Ram=0
³ ³ ³ ÃÄSendBit 0/74 Ram=0
³ ³ ³ ÃÄflipout 0/7 Ram=0
³ ³ ³ ÀÄSendBit 0/74 Ram=0
³ ³ ÃÄSendByte 0/75 Ram=4
³ ³ ³ ÃÄfcsbit (Inline) Ram=3
³ ³ ³ ÃÄflipout 0/7 Ram=0
³ ³ ³ ÃÄSendBit 0/74 Ram=0
³ ³ ³ ÃÄflipout 0/7 Ram=0
³ ³ ³ ÀÄSendBit 0/74 Ram=0
³ ³ ÃÄSendByte 0/75 Ram=4
³ ³ ³ ÃÄfcsbit (Inline) Ram=3
³ ³ ³ ÃÄflipout 0/7 Ram=0
³ ³ ³ ÃÄSendBit 0/74 Ram=0
³ ³ ³ ÃÄflipout 0/7 Ram=0
³ ³ ³ ÀÄSendBit 0/74 Ram=0
³ ³ ÀÄSendByte 0/75 Ram=4
³ ³ ÃÄfcsbit (Inline) Ram=3
³ ³ ÃÄflipout 0/7 Ram=0
³ ³ ÃÄSendBit 0/74 Ram=0
³ ³ ÃÄflipout 0/7 Ram=0
³ ³ ÀÄSendBit 0/74 Ram=0
³ ÀÄdelay_ms 0/21 Ram=1
ÃÄbeep 0/38 Ram=6
³ ÃÄdelay_us 0/14 Ram=1
³ ÀÄdelay_us 0/14 Ram=1
ÃÄdelay_ms 0/21 Ram=1
ÃÄbeep 0/38 Ram=6
³ ÃÄdelay_us 0/14 Ram=1
³ ÀÄdelay_us 0/14 Ram=1
ÃÄdelay_ms 0/21 Ram=1
ÃÄobjizdka 0/73 Ram=1
³ ÃÄdelay_ms 0/21 Ram=1
³ ÃÄbeep 0/38 Ram=6
³ ³ ÃÄdelay_us 0/14 Ram=1
³ ³ ÀÄdelay_us 0/14 Ram=1
³ ÃÄdelay_ms 0/21 Ram=1
³ ÃÄbeep 0/38 Ram=6
³ ³ ÃÄdelay_us 0/14 Ram=1
³ ³ ÀÄdelay_us 0/14 Ram=1
³ ÀÄdelay_ms 0/21 Ram=1
ÃÄ@goto10341 0/6 Ram=0
ÃÄdelay_ms 0/21 Ram=1
ÃÄdelay_ms 0/21 Ram=1
ÃÄbeep 0/38 Ram=6
³ ÃÄdelay_us 0/14 Ram=1
³ ÀÄdelay_us 0/14 Ram=1
ÃÄdelay_ms 0/21 Ram=1
ÃÄbeep 0/38 Ram=6
³ ÃÄdelay_us 0/14 Ram=1
³ ÀÄdelay_us 0/14 Ram=1
ÃÄ@goto10355 0/7 Ram=0
ÃÄdelay_ms 0/21 Ram=1
ÃÄdelay_ms 0/21 Ram=1
ÃÄdelay_ms 0/21 Ram=1
ÃÄdelay_ms 0/21 Ram=1
ÀÄcikcak 0/172 Ram=1
ÃÄ@goto10199 0/7 Ram=0
ÃÄ@goto10214 0/6 Ram=0
ÀÄdelay_ms 0/21 Ram=1
/roboti/istrobot/merkur/PIC16F873/prg.bat
0,0 → 1,6
call picpgr stop lpt2
call picpgr erase pic16f873 lpt2
call picpgr program main.hex hex pic16f873 lpt2
call picpgr run lpt2
pause
call picpgr stop lpt2
/roboti/istrobot/merkur/PIC16F873/vssver.scc
Cannot display: file marked as a binary type.
svn:mime-type = application/octet-stream
Property changes:
Added: svn:mime-type
+application/octet-stream
\ No newline at end of property
/roboti/istrobot/merkur/dokumentace/merkur.doc
Cannot display: file marked as a binary type.
svn:mime-type = application/octet-stream
Property changes:
Added: svn:mime-type
+application/octet-stream
\ No newline at end of property
/roboti/istrobot/merkur/dokumentace/obrazky/P3200001.JPG
Cannot display: file marked as a binary type.
svn:mime-type = application/octet-stream
Property changes:
Added: svn:mime-type
+application/octet-stream
\ No newline at end of property
/roboti/istrobot/merkur/dokumentace/obrazky/P3200002.JPG
Cannot display: file marked as a binary type.
svn:mime-type = application/octet-stream
Property changes:
Added: svn:mime-type
+application/octet-stream
\ No newline at end of property
/roboti/istrobot/merkur/dokumentace/obrazky/P4110011.JPG
Cannot display: file marked as a binary type.
svn:mime-type = application/octet-stream
Property changes:
Added: svn:mime-type
+application/octet-stream
\ No newline at end of property
/roboti/istrobot/merkur/dokumentace/obrazky/P4110012.JPG
Cannot display: file marked as a binary type.
svn:mime-type = application/octet-stream
Property changes:
Added: svn:mime-type
+application/octet-stream
\ No newline at end of property
/roboti/istrobot/merkur/dokumentace/obrazky/P4110013.JPG
Cannot display: file marked as a binary type.
svn:mime-type = application/octet-stream
Property changes:
Added: svn:mime-type
+application/octet-stream
\ No newline at end of property
/roboti/istrobot/merkur/dokumentace/obrazky/P4110014.JPG
Cannot display: file marked as a binary type.
svn:mime-type = application/octet-stream
Property changes:
Added: svn:mime-type
+application/octet-stream
\ No newline at end of property
/roboti/istrobot/merkur/dokumentace/obrazky/P5110007.JPG
Cannot display: file marked as a binary type.
svn:mime-type = application/octet-stream
Property changes:
Added: svn:mime-type
+application/octet-stream
\ No newline at end of property
/roboti/istrobot/merkur/dokumentace/obrazky/P5110008.JPG
Cannot display: file marked as a binary type.
svn:mime-type = application/octet-stream
Property changes:
Added: svn:mime-type
+application/octet-stream
\ No newline at end of property
/roboti/istrobot/merkur/dokumentace/obrazky/P5110009.JPG
Cannot display: file marked as a binary type.
svn:mime-type = application/octet-stream
Property changes:
Added: svn:mime-type
+application/octet-stream
\ No newline at end of property
/roboti/istrobot/merkur/dokumentace/obrazky/P5110010.JPG
Cannot display: file marked as a binary type.
svn:mime-type = application/octet-stream
Property changes:
Added: svn:mime-type
+application/octet-stream
\ No newline at end of property
/roboti/istrobot/merkur/dokumentace/obrazky/PIC16F88/AX25.c
0,0 → 1,135
#nolist
//#define PTT PIN_A2 // PTT control
//#define TXo PIN_C0 // To the transmitter modulator
#define PERIODAH delay_us(222) // Halfperiod H 222;78/1200 500;430/500
#define TAILH delay_us(78)
#define PERIODAL delay_us(412) // Halfperiod L 412;345/1200 1000;880/500
#define TAILL delay_us(345)
#byte STATUS = 3 // CPUs status register
 
byte SendData[16] = {'A'<<1, 'L'<<1, 'L'<<1, ' '<<1, ' '<<1, ' '<<1, 0x60,
'C'<<1, 'Z'<<1, '0'<<1, 'R'<<1, 'R'<<1, 'R'<<1, 0x61,
0x03, 0xF0};
 
boolean bit;
int fcslo, fcshi; // variabloes for calculating FCS (CRC)
int stuff; // stuff counter for extra 0
int flag_flag; // if it is sending flag (7E)
int fcs_flag; // if it is sending Frame Check Sequence
int i; // for for
 
void flipout() //flips the state of output pin a_1
{
stuff = 0; //since this is a 0, reset the stuff counter
if (bit)
{
bit=FALSE; //if the state of the pin was low, make it high.
}
else
{
bit=TRUE; //if the state of the pin was high make it low
}
}
 
void fcsbit(byte tbyte)
{
#asm
BCF STATUS,0
RRF fcshi,F // rotates the entire 16 bits
RRF fcslo,F // to the right
#endasm
if (((STATUS & 0x01)^(tbyte)) ==0x01)
{
fcshi = fcshi^0x84;
fcslo = fcslo^0x08;
}
}
 
void SendBit ()
{
if (bit)
{
output_high(TXo);
PERIODAH;
output_low(TXo);
PERIODAH;
output_high(TXo);
PERIODAH;
output_low(TXo);
TAILH;
}
else
{
output_high(TXo);
PERIODAL;
output_low(TXo);
TAILL;
};
}
 
void SendByte (byte inbyte)
{
int k, bt;
 
for (k=0;k<8;k++) //do the following for each of the 8 bits in the byte
{
bt = inbyte & 0x01; //strip off the rightmost bit of the byte to be sent (inbyte)
if ((fcs_flag == FALSE) & (flag_flag == FALSE)) fcsbit(bt); //do FCS calc, but only if this
//is not a flag or fcs byte
if (bt == 0)
{
flipout();
} // if this bit is a zero, flip the output state
else
{ //otherwise if it is a 1, do the following:
if (flag_flag == FALSE) stuff++; //increment the count of consequtive 1's
if ((flag_flag == FALSE) & (stuff == 5))
{ //stuff an extra 0, if 5 1's in a row
SendBit();
flipout(); //flip the output state to stuff a 0
}//end of if
}//end of else
// delay_us(850); //introduces a delay that creates 1200 baud
SendBit();
inbyte = inbyte>>1; //go to the next bit in the byte
}//end of for
}//end of SendByte
 
void SendPacket(char *data)
{
bit=FALSE;
 
fcslo=fcshi=0xFF; //The 2 FCS Bytes are initialized to FF
stuff = 0; //The variable stuff counts the number of 1's in a row. When it gets to 5
// it is time to stuff a 0.
 
// output_low(PTT); // Blinking LED
// delay_ms(1000);
// output_high(PTT);
 
flag_flag = TRUE; //The variable flag is true if you are transmitted flags (7E's) false otherwise.
fcs_flag = FALSE; //The variable fcsflag is true if you are transmitting FCS bytes, false otherwise.
 
for(i=0; i<10; i++) SendByte(0x7E); //Sends flag bytes. Adjust length for txdelay
//each flag takes approx 6.7 ms
flag_flag = FALSE; //done sending flags
 
for(i=0; i<16; i++) SendByte(SendData[i]); //send the packet bytes
 
for(i=0; 0 != *data; i++)
{
SendByte(*data); //send the packet bytes
data++;
};
 
fcs_flag = TRUE; //about to send the FCS bytes
fcslo =fcslo^0xff; //must XOR them with FF before sending
fcshi = fcshi^0xff;
SendByte(fcslo); //send the low byte of fcs
SendByte(fcshi); //send the high byte of fcs
fcs_flag = FALSE; //done sending FCS
flag_flag = TRUE; //about to send flags
SendByte(0x7e); // Send a flag to end packet
}
 
#list
/roboti/istrobot/merkur/dokumentace/obrazky/PIC16F88/merkur.BAK
0,0 → 1,331
////////////////////////////////////////////////////////////////////////////////
// //
// Program pro robota Merkur //
// //
////////////////////////////////////////////////////////////////////////////////
#include "merkur.h"
 
//#define DEBUG
 
#define TXo PIN_A3 // To the transmitter modulator
#include "AX25.c" // podprogram pro prenos telemetrie
 
unsigned int8 sensors; // pomocna promenna pro cteni cidel na caru
unsigned int8 line; // na ktere strane byla detekovana cara
unsigned int8 speed; // rychlost zataceni
unsigned int8 rovinka; // pocitadlo pro zjisteni rovneho useku
unsigned int8 last; // kde byla cara, kdyz byly minule cidla mimo
unsigned int8 movement; // obsahuje aktualni smer zataceni
unsigned int8 dira; // pocita dobu po kterou je ztracena cara
 
// Konstanty pro dynamiku pohybu
#define T_DIRA 120 // po jakem case zataceni se detekuje dira
#define INC_SPEED 1 // prirustek rychlosti v jednom kroku
#define FW_POMALU 230 // trochu mimo caru vnitrni pas
#define FW_ZATACKA 240 // rychlost vnejsiho kola pri zataceni
#define FW_STREDNE 240 // trochu mimo caru vnejsi pas
#define COUVANI 750 // couvnuti zpet na caru, po detekci diry
#define PRES_DIRU 300 // predpokladana velikost diry
#define MAX_ROVINKA (255-FW_STREDNE) // maximalni rychlost na rovince
#define TRESHOLD 6 // rozhodovaci uroven komparatoru, 0xF = 0.75*Vdd
#define BUMPER_TRESHOLD 128 // rozhodovaci uroven cidla na cihlu
#define CIK_CAK 30000 // maximalni rozkmit pri hledani cary
#define T_CIHLA 50 // perioda detekce cihly
 
//motory //Napred vypnout potom zapnout!
#define FR output_low(PIN_B5); output_high(PIN_B4) // Vpred
#define FL output_low(PIN_B7); output_high(PIN_B6)
#define BR output_low(PIN_B4); output_high(PIN_B5) // Vzad
#define BL output_low(PIN_B6); output_high(PIN_B7)
#define STOPR output_low(PIN_B4);output_low(PIN_B5) // Zastav
#define STOPL output_low(PIN_B6);output_low(PIN_B7)
 
#define L 0b10 // left
#define R 0b01 // right
#define S 0b11 // straight
 
//cidla
#define RSENSOR C2OUT // Senzory na caru
#define LSENSOR C1OUT
#define BUMPER PIN_A4 // Senzor na cihlu
 
#define DIAG_SERVO PIN_B3 // Propojka pro diagnosticky mod
#define DIAG_SENSORS PIN_B2 // Propojka pro diagnosticky mod
 
#DEFINE SOUND_HI PIN_A6 // komplementarni vystupy pro piezo pipak
#DEFINE SOUND_LO PIN_A7
 
char AXstring[40]; // Buffer pro prenos telemetrie
 
// makro pro PWM
#define GO(motor, direction, power) if(get_timer0()<=power) \
{direction##motor;} else {stop##motor;}
 
#int_TIMER2
void TIMER2_isr()
{
if (speed<255) speed+=INC_SPEED;
if (rovinka<MAX_ROVINKA) rovinka++;
if (dira<=T_DIRA) dira++;
}
// Primitivni Pipani
void beep(unsigned int16 period, unsigned int16 length)
{
unsigned int16 nn;
 
for(nn=length; nn>0; nn--)
{
output_high(SOUND_HI);output_low(SOUND_LO);
delay_us(period);
output_high(SOUND_LO);output_low(SOUND_HI);
delay_us(period);
}
}
/******************************************************************************/
void diagnostika() // vyzkousi funkci pohonu a cidel
{
unsigned int16 n;
 
while (input(DIAG_SERVO)) // Propojka, ktera spousti diagnostiku
{
for (n=500; n<800; n+=100)
{
beep(n,n); //beep UP
};
Delay_ms(1000);
//zastav vse
STOPL; STOPR;
//pravy pas
FR; Delay_ms(1000); STOPR; Delay_ms(1000);
BR; Delay_ms(1000); STOPR; Delay_ms(1000);
Beep(880,100); Delay_ms(1000);
//levy pas
FL; Delay_ms(1000); STOPL; Delay_ms(1000);
BL; Delay_ms(1000); STOPL; Delay_ms(1000);
Beep(880,100); Delay_ms(1000);
//oba pasy
FL; FR; Delay_ms(1000); STOPL; STOPR; Delay_ms(1000);
BL; BR; Delay_ms(1000); STOPL; STOPR; Delay_ms(1000);
};
while (input(DIAG_SENSORS)) // spusteni diagnostiky cidel
{
if (RSENSOR) beep(900,500);
if (LSENSOR) beep(800,500);
if ((read_adc(ADC_READ_ONLY)<BUMPER_TRESHOLD)) beep(1000,500);
};
}
///////////////////////////////////////////////////////////////////////////////
void cikcak() // najde ztracenou caru
{
unsigned int16 n;
sem1:
n=CIK_CAK;
while (0==RSENSOR||LSENSOR) // zkontroluj caru
{
if (n==CIK_CAK) // zmen smer zataceni
{
n=0;
switch(movement)
{
case L:
FL;BR;
movement=R;
break;
case R:
FR;BL;
movement=L;
break;
case S:
FL;BR;
movement=R;
n=CIK_CAK/2;
break;
}
}
n++;
}
STOPL;STOPR;
line = RSENSOR; // cteni senzoru na caru
line |= LSENSOR << 1;
if (line==0) goto sem1;
// nasli jsme caru
line=S;
}
///////////////////////////////////////////////////////////////////////////////
void objizdka() // objede cihlu
{
unsigned int16 n;
 
BL;BR;Delay_ms(150);
STOPR;STOPL;
beep(900,1000);
// movement=S;
// cikcak();
 
BR; FL; Delay_ms(270); // otoc se 70° do prava
 
FR; FL; Delay_ms(500); // popojed rovne
 
BL; Delay_ms(30); // otoc se 90° do leva
STOPL; FR; Delay_ms(500);
 
FR; FL; Delay_ms(100); // popojed rovne na slepo
for(n=40000;n>0;n--) // popojed rovne ale kontroluj caru
{
line = RSENSOR; // cteni senzoru na caru
line |= LSENSOR << 1;
if (line!=0) {Delay_ms(150); break;}
// Delay_ms(1);
}
 
BR; FL; // otoc se 60° do prava
for(n=40000;n>0;n--)
{
line = RSENSOR; // cteni senzoru na caru
line |= LSENSOR << 1;
if (line!=0) break;
// Delay_ms(1);
}
STOPR; STOPL;
 
movement=L; //R;
cikcak();
dira=0;
}
///////////////////////////////////////////////////////////////////////////////
void prejeddiru() // vyresi diru
{
unsigned int16 n;
unsigned int8 speed_dira;
 
STOPL;STOPR;
speed_dira=speed;
beep(1000,500);
switch (movement) //vrat se zpet na caru
{
case L:
for (n=COUVANI;n>0;n--) {GO(R,B,speed_dira); Delay_ms(1);}
STOPL;STOPR;
break;
case R:
for (n=COUVANI;n>0;n--) {GO(L,B,speed_dira); Delay_ms(1);}
STOPL;STOPR;
break;
case S:
goto sem;
break;
}
beep(1000,500);
 
FR;FL; //popojed rovne
for(n=PRES_DIRU;n>0;n--)
{
line = RSENSOR; // cteni senzoru na caru
line |= LSENSOR << 1;
if (line!=0) break;
Delay_ms(1);
}
sem:
STOPL; STOPR;
movement=S;
cikcak(); // najdi caru
dira=0;
}
///////////////////////////////////////////////////////////////////////////////
void main()
{
unsigned int16 n; // pro FOR
 
STOPL; STOPR; // prepne vystupy na ovladani motoru na output a zastavi
 
setup_oscillator(OSC_4MHZ|OSC_INTRC); // 4 MHz interni RC oscilator
 
port_b_pullups(TRUE); // pullups pro piano na diagnostiku
setup_spi(FALSE);
setup_timer_0(RTCC_INTERNAL|RTCC_DIV_1); // Casovac pro PWM
 
setup_timer_2(T2_DIV_BY_4,255,10); // Casovac pro regulaci
// preruseni kazdych 10ms
setup_adc_ports(sAN2|VSS_VDD); // nastaveni A/D prevodniku pro naraznik
setup_adc(ADC_CLOCK_INTERNAL);
set_adc_channel(2);
setup_timer_1(T1_INTERNAL|T1_DIV_BY_1); // Casovac pro naraznik
setup_ccp1(CCP_COMPARE_RESET_TIMER);
CCP_1=(2^10)-1; // prevod kazdou 1ms
 
setup_comparator(A0_VR_A1_VR); // inicializace komparatoru pro cidla cary
setup_vref(VREF_HIGH|TRESHOLD); // 32 kroku od 0.25 do 0.75 Vdd
 
Beep(1000,200); //double beep
Delay_ms(50);
Beep(1000,200);
Delay_ms(1000); // 1s
 
// povoleni rizeni rychlosti zataceni pres preruseni
enable_interrupts(INT_TIMER2);
enable_interrupts(GLOBAL);
 
/*---------------------------------------------------------------------------*/
sensors=S;
line=S;
last=S;
movement=S;
speed=FW_POMALU;
 
diagnostika();
//cikcak(); // toc se, abys nasel caru
Delay_ms(500);
Beep(1000,200);
Delay_ms(500);
 
while(true) // hlavni smycka (jizda podle cary)
{
sensors = RSENSOR; // cteni senzoru na caru
sensors |= LSENSOR << 1;
 
if ((read_adc(ADC_READ_ONLY)<BUMPER_TRESHOLD) && (dira<=T_CIHLA)) objizdka();
 
switch (sensors) // zatacej podle toho, kde vidis caru
{
case S: // rovne
FL; FR; // pokud se jede dlouho rovne, tak pridej
dira=0;
movement=S;
continue;
case L: // trochu vlevo
GO(L, F, FW_POMALU+rovinka); GO(R, F, FW_STREDNE+rovinka);
line=L;
dira=0;
movement=L;
continue;
case R: // trochu vpravo
GO(R, F, FW_POMALU+rovinka); GO(L, F, FW_STREDNE+rovinka);
line=R;
dira=0;
movement=R;
continue;
default: // kdyz jsou obe cidla mimo caru, tak pokracuj dal
}
rovinka=0;
if (dira>=T_DIRA) prejeddiru();
if (last!=line) // pokud si prejel caru z jedne strany na druhou
// stranu, tak zabrzdi
{
last=line;
speed=FW_ZATACKA;
}
if (L==line) // kdyz jsou obe cidla mimo caru, zatoc na caru
{
STOPL;
GO(R, F, speed);
movement=L;
}
else
{
STOPR;
GO(L, F, speed);
movement=R;
}
} // while(true)
}
 
/roboti/istrobot/merkur/dokumentace/obrazky/PIC16F88/merkur.c
0,0 → 1,332
////////////////////////////////////////////////////////////////////////////////
// //
// Program pro robota Merkur //
// //
////////////////////////////////////////////////////////////////////////////////
#include "merkur.h"
 
//#define DEBUG
 
#define TXo PIN_A3 // To the transmitter modulator
#include "AX25.c" // podprogram pro prenos telemetrie
 
unsigned int8 sensors; // pomocna promenna pro cteni cidel na caru
unsigned int8 line; // na ktere strane byla detekovana cara
unsigned int8 speed; // rychlost zataceni
unsigned int8 rovinka; // pocitadlo pro zjisteni rovneho useku
unsigned int8 last; // kde byla cara, kdyz byly minule cidla mimo
unsigned int8 movement; // obsahuje aktualni smer zataceni
unsigned int8 dira; // pocita dobu po kterou je ztracena cara
 
// Konstanty pro dynamiku pohybu
#define T_DIRA 120 // po jakem case zataceni se detekuje dira
#define INC_SPEED 1 // prirustek rychlosti v jednom kroku
#define FW_POMALU 230 // trochu mimo caru vnitrni pas
#define FW_ZATACKA 240 // rychlost vnejsiho kola pri zataceni
#define FW_STREDNE 240 // trochu mimo caru vnejsi pas
#define COUVANI 750 // couvnuti zpet na caru, po detekci diry
#define PRES_DIRU 300 // predpokladana velikost diry
#define MAX_ROVINKA (255-FW_STREDNE) // maximalni rychlost na rovince
#define TRESHOLD 6 // rozhodovaci uroven komparatoru, 0xF = 0.75*Vdd
#define BUMPER_TRESHOLD 128 // rozhodovaci uroven cidla na cihlu
#define CIK_CAK 30000 // maximalni rozkmit pri hledani cary
#define T_CIHLA 50 // perioda detekce cihly
 
//motory //Napred vypnout potom zapnout!
#define FR output_low(PIN_B5); output_high(PIN_B4) // Vpred
#define FL output_low(PIN_B7); output_high(PIN_B6)
#define BR output_low(PIN_B4); output_high(PIN_B5) // Vzad
#define BL output_low(PIN_B6); output_high(PIN_B7)
#define STOPR output_low(PIN_B4);output_low(PIN_B5) // Zastav
#define STOPL output_low(PIN_B6);output_low(PIN_B7)
 
#define L 0b10 // left
#define R 0b01 // right
#define S 0b11 // straight
 
//cidla
#define RSENSOR C2OUT // Senzory na caru
#define LSENSOR C1OUT
#define BUMPER PIN_A4 // Senzor na cihlu
 
#define DIAG_SERVO PIN_B3 // Propojka pro diagnosticky mod
#define DIAG_SENSORS PIN_B2 // Propojka pro diagnosticky mod
 
#DEFINE SOUND_HI PIN_A6 // komplementarni vystupy pro piezo pipak
#DEFINE SOUND_LO PIN_A7
 
char AXstring[40]; // Buffer pro prenos telemetrie
 
// makro pro PWM
#define GO(motor, direction, power) if(get_timer0()<=power) \
{direction##motor;} else {stop##motor;}
 
#int_TIMER2
void TIMER2_isr()
{
if (speed<255) speed+=INC_SPEED;
if (rovinka<MAX_ROVINKA) rovinka++;
if (dira<=T_DIRA) dira++;
}
// Primitivni Pipani
void beep(unsigned int16 period, unsigned int16 length)
{
unsigned int16 nn;
 
for(nn=length; nn>0; nn--)
{
output_high(SOUND_HI);output_low(SOUND_LO);
delay_us(period);
output_high(SOUND_LO);output_low(SOUND_HI);
delay_us(period);
}
}
/******************************************************************************/
void diagnostika() // vyzkousi funkci pohonu a cidel
{
unsigned int16 n;
 
while (input(DIAG_SERVO)) // Propojka, ktera spousti diagnostiku
{
for (n=500; n<800; n+=100)
{
beep(n,n); //beep UP
};
Delay_ms(1000);
//zastav vse
STOPL; STOPR;
//pravy pas
FR; Delay_ms(1000); STOPR; Delay_ms(1000);
BR; Delay_ms(1000); STOPR; Delay_ms(1000);
Beep(880,100); Delay_ms(1000);
//levy pas
FL; Delay_ms(1000); STOPL; Delay_ms(1000);
BL; Delay_ms(1000); STOPL; Delay_ms(1000);
Beep(880,100); Delay_ms(1000);
//oba pasy
FL; FR; Delay_ms(1000); STOPL; STOPR; Delay_ms(1000);
BL; BR; Delay_ms(1000); STOPL; STOPR; Delay_ms(1000);
};
while (input(DIAG_SENSORS)) // spusteni diagnostiky cidel
{
if (RSENSOR) beep(900,500);
if (LSENSOR) beep(800,500);
if ((read_adc(ADC_READ_ONLY)<BUMPER_TRESHOLD)) beep(1000,500);
};
}
///////////////////////////////////////////////////////////////////////////////
void cikcak() // najde ztracenou caru
{
unsigned int16 n;
sem1:
n=CIK_CAK;
while (0==RSENSOR||LSENSOR) // zkontroluj caru
{
if (n==CIK_CAK) // zmen smer zataceni
{
n=0;
switch(movement)
{
case L:
FL;BR;
movement=R;
break;
case R:
FR;BL;
movement=L;
break;
case S:
FL;BR;
movement=R;
n=CIK_CAK/2;
break;
}
}
n++;
}
STOPL;STOPR;
line = RSENSOR; // cteni senzoru na caru
line |= LSENSOR << 1;
if (line==0) goto sem1;
// nasli jsme caru
line=S;
}
///////////////////////////////////////////////////////////////////////////////
void objizdka() // objede cihlu
{
unsigned int16 n;
 
BL;BR;Delay_ms(150);
STOPR;STOPL;
beep(900,1000);
// movement=S;
// cikcak();
 
BR; FL; Delay_ms(270); // otoc se 70° do prava
 
FR; FL; Delay_ms(500); // popojed rovne
 
BL; Delay_ms(30); // otoc se 90° do leva
STOPL; FR; Delay_ms(500);
 
FR; FL; Delay_ms(100); // popojed rovne na slepo
for(n=40000;n>0;n--) // popojed rovne ale kontroluj caru
{
line = RSENSOR; // cteni senzoru na caru
line |= LSENSOR << 1;
if (line!=0) {Delay_ms(150); break;}
// Delay_ms(1);
}
 
BR; FL; // otoc se 60° do prava
for(n=40000;n>0;n--)
{
line = RSENSOR; // cteni senzoru na caru
line |= LSENSOR << 1;
if (line!=0) break;
// Delay_ms(1);
}
STOPR; STOPL;
 
movement=L; //R;
cikcak();
dira=0;
}
///////////////////////////////////////////////////////////////////////////////
void prejeddiru() // vyresi diru
{
unsigned int16 n;
unsigned int8 speed_dira;
 
STOPL;STOPR;
speed_dira=speed;
beep(1000,500);
switch (movement) //vrat se zpet na caru
{
case L:
for (n=COUVANI;n>0;n--) {GO(R,B,speed_dira); Delay_ms(1);}
STOPL;STOPR;
break;
case R:
for (n=COUVANI;n>0;n--) {GO(L,B,speed_dira); Delay_ms(1);}
STOPL;STOPR;
break;
case S:
goto sem;
break;
}
beep(1000,500);
 
FR;FL; //popojed rovne
for(n=PRES_DIRU;n>0;n--)
{
line = RSENSOR; // cteni senzoru na caru
line |= LSENSOR << 1;
if (line!=0) break;
Delay_ms(1);
}
sem:
STOPL; STOPR;
movement=S;
cikcak(); // najdi caru
dira=0;
}
///////////////////////////////////////////////////////////////////////////////
void main()
{
unsigned int16 n; // pro FOR
 
STOPL; STOPR; // prepne vystupy na ovladani motoru na output a zastavi
 
setup_oscillator(OSC_4MHZ|OSC_INTRC); // 4 MHz interni RC oscilator
 
port_b_pullups(TRUE); // pullups pro piano na diagnostiku
setup_spi(FALSE);
setup_timer_0(RTCC_INTERNAL|RTCC_DIV_1); // Casovac pro PWM
 
setup_timer_2(T2_DIV_BY_4,255,10); // Casovac pro regulaci
// preruseni kazdych 10ms
setup_adc_ports(sAN2|VSS_VDD); // nastaveni A/D prevodniku pro naraznik
setup_adc(ADC_CLOCK_INTERNAL);
set_adc_channel(2);
setup_timer_1(T1_INTERNAL|T1_DIV_BY_1); // Casovac pro naraznik
setup_ccp1(CCP_COMPARE_RESET_TIMER);
CCP_1=(2^10)-1; // prevod kazdou 1ms
 
setup_comparator(A0_VR_A1_VR); // inicializace komparatoru pro cidla cary
setup_vref(VREF_HIGH|TRESHOLD); // 32 kroku od 0.25 do 0.75 Vdd
 
Beep(1000,200); //double beep
Delay_ms(50);
Beep(1000,200);
Delay_ms(1000); // 1s
 
// povoleni rizeni rychlosti zataceni pres preruseni
enable_interrupts(INT_TIMER2);
enable_interrupts(GLOBAL);
 
/*---------------------------------------------------------------------------*/
sensors=S;
line=S;
last=S;
movement=S;
speed=FW_POMALU;
 
diagnostika();
//cikcak(); // toc se, abys nasel caru
Delay_ms(500);
Beep(1000,200);
Delay_ms(500);
 
while(true) // hlavni smycka (jizda podle cary)
{
sensors = RSENSOR; // cteni senzoru na caru
sensors |= LSENSOR << 1;
 
if ((read_adc(ADC_READ_ONLY)<BUMPER_TRESHOLD) && \
(dira<=T_CIHLA)) objizdka();
 
switch (sensors) // zatacej podle toho, kde vidis caru
{
case S: // rovne
FL; FR; // pokud se jede dlouho rovne, tak pridej
dira=0;
movement=S;
continue;
case L: // trochu vlevo
GO(L, F, FW_POMALU+rovinka); GO(R, F, FW_STREDNE+rovinka);
line=L;
dira=0;
movement=L;
continue;
case R: // trochu vpravo
GO(R, F, FW_POMALU+rovinka); GO(L, F, FW_STREDNE+rovinka);
line=R;
dira=0;
movement=R;
continue;
default: // kdyz jsou obe cidla mimo caru, tak pokracuj dal
}
rovinka=0;
if (dira>=T_DIRA) prejeddiru();
if (last!=line) // pokud si prejel caru z jedne strany na druhou
// stranu, tak zabrzdi
{
last=line;
speed=FW_ZATACKA;
}
if (L==line) // kdyz jsou obe cidla mimo caru, zatoc na caru
{
STOPL;
GO(R, F, speed);
movement=L;
}
else
{
STOPR;
GO(L, F, speed);
movement=R;
}
} // while(true)
}
 
/roboti/istrobot/merkur/dokumentace/obrazky/PIC16F88/tank.BAK
0,0 → 1,350
#include "tank.h"
 
#define DEBUG
 
#define TXo PIN_A3 // To the transmitter modulator
#include "AX25.c" // podprogram pro prenos telemetrie
 
unsigned int8 sensors; // pomocna promenna pro cteni cidel na caru
unsigned int8 line; // na ktere strane byla detekovana cara
unsigned int8 speed; // rychlost zataceni
unsigned int8 rovinka; // pocitadlo pro zjisteni rovneho useku
unsigned int8 last; // kde byla cara, kdyz byly minule cidla mimo
unsigned int8 movement; // obsahuje aktualni smer zataceni
unsigned int8 dira; // pocita dobu po kterou je ztracena cara
unsigned int8 cihla; // urcuje za jak dlouho muze byt znova detekovana cihla
 
// Konstanty pro dynamiku pohybu
#define T_DIRA 85 // po jakem case zataceni se detekuje dira
#define INC_SPEED 1 // prirustek rychlosti v jednom kroku
#define FW_POMALU 230 // trochu mimo caru vnitrni pas
#define FW_ZATACKA 200 // rychlost vnejsiho kola pri zataceni
#define FW_STREDNE 240 // trochu mimo caru vnejsi pas
#define COUVANI 600 // couvnuti zpet na caru, po detekci diry
#define PRES_DIRU 150
#define MAX_ROVINKA (255-FW_STREDNE)
#define TRESHOLD 10 // rozhodovaci uroven komparatoru, 0xF = 0.75*Vdd
#define BUMPER_TRESHOLD 128
#define CIK_CAK 20000
#define T_CIHLA 100 // perioda detekce cihly
 
//motory //Napred vypnout potom zapnout!
#define FR output_low(PIN_B5); output_high(PIN_B4) // Vpred
#define FL output_low(PIN_B7); output_high(PIN_B6)
#define BR output_low(PIN_B4); output_high(PIN_B5) // Vzad
#define BL output_low(PIN_B6); output_high(PIN_B7)
#define STOPR output_low(PIN_B4);output_low(PIN_B5) // Zastav
#define STOPL output_low(PIN_B6);output_low(PIN_B7)
 
#define L 0b10 // left
#define R 0b01 // right
#define S 0b11 // straight
 
//cidla
#define RSENSOR C2OUT // Senzory na caru
#define LSENSOR C1OUT
#define BUMPER PIN_A4 // Senzor na cihlu
 
#define DIAG_SERVO PIN_B3 // Propojka pro diagnosticky mod
#define DIAG_SENSORS PIN_B2 // Propojka pro diagnosticky mod
 
#DEFINE SOUND_HI PIN_A6 // komplementarni vystupy pro piezo pipak
#DEFINE SOUND_LO PIN_A7
 
char AXstring[40]; // Buffer pro prenos telemetrie
 
// makro pro PWM
#define GO(motor, direction, power) if(get_timer0()<=power) \
{direction##motor;} else {stop##motor;}
 
#int_TIMER2
void TIMER2_isr()
{
if (speed<255) speed+=INC_SPEED;
if (rovinka<MAX_ROVINKA) rovinka++;
if (dira<=T_DIRA) dira++;
if (cihla>0) cihla--;
}
// Primitivni Pipani
void beep(unsigned int16 period, unsigned int16 length)
{
unsigned int16 nn;
 
for(nn=length; nn>0; nn--)
{
output_high(SOUND_HI);output_low(SOUND_LO);
delay_us(period);
output_high(SOUND_LO);output_low(SOUND_HI);
delay_us(period);
}
}
/******************************************************************************/
void diagnostika()
{
unsigned int16 n;
 
while (input(DIAG_SERVO)) // Propojka, ktera spousti diagnostiku
{
for (n=500; n<800; n+=100)
{
beep(n,n); //beep UP
};
Delay_ms(1000);
//zastav vse
STOPL; STOPR;
//pravy pas
FR; Delay_ms(1000); STOPR; Delay_ms(1000);
BR; Delay_ms(1000); STOPR; Delay_ms(1000);
Beep(880,100); Delay_ms(1000);
//levy pas
FL; Delay_ms(1000); STOPL; Delay_ms(1000);
BL; Delay_ms(1000); STOPL; Delay_ms(1000);
Beep(880,100); Delay_ms(1000);
//oba pasy
FL; FR; Delay_ms(1000); STOPL; STOPR; Delay_ms(1000);
BL; BR; Delay_ms(1000); STOPL; STOPR; Delay_ms(1000);
};
while (input(DIAG_SENSORS))
{
int ls, rs;
while(!input(BUMPER)){beep(1100,100); Delay_ms(50);}
set_adc_channel(RSENSOR);
Delay_us(20);
rs=read_adc();
set_adc_channel(LSENSOR);
Delay_us(20);
ls=read_adc();
sprintf(AXstring,"L: %U R: %U\0", ls, rs); // Convert DATA to String.
SendPacket(&AXstring[0]);
delay_ms(1000);
};
}
///////////////////////////////////////////////////////////////////////////////
void cikcak()
{
unsigned int16 n;
 
line = RSENSOR; // cteni senzoru na caru
line |= LSENSOR << 1;
if (line!=0) return;
 
n=0;
switch(movement) // podivej se na druhou stranu nez se jelo
{
case L:
FL;BR;
movement=R;
break;
case R:
FR;BL;
movement=L;
break;
case S:
FL;BR;
movement=R;
n=CIK_CAK/2;
break;
}
while (0==(RSENSOR|LSENSOR)) // zkontroluj caru
{
if (n==CIK_CAK) // zmen smer zataceni
{
n=0;
switch(movement)
{
case L:
FL;BR;
movement=R;
break;
case R:
FR;BL;
movement=L;
break;
}
}
n++;
}
switch(movement)
{
case L:
FL;BR;
movement=R;
break;
case R:
FR;BL;
movement=L;
break;
}
Delay_ms(50);
STOPL;STOPR; // nasli jsme caru
line=S;
}
///////////////////////////////////////////////////////////////////////////////
void objizdka() // objede cihlu
{
unsigned int16 n;
 
BL;BR;Delay_ms(200);
STOPR;STOPL;
beep(900,1000);
movement=S;
cikcak();
 
BR; FL; Delay_ms(215); // otoc se 70° do prava
 
FR; FL; Delay_ms(600); // popojed rovne
 
BL; Delay_ms(50); // otoc se 90° do leva
STOPL; FR; Delay_ms(550);
 
FR; FL; Delay_ms(100); // popojed rovne na slepo
for(n=600;n>0;n--) // popojed rovne ale kontroluj caru
{
line = RSENSOR; // cteni senzoru na caru
line |= LSENSOR << 1;
if (line!=0) {Delay_ms(50); break;}
Delay_ms(1);
}
 
BR; // otoc se 60° do prava
for(n=600;n>0;n--)
{
line = RSENSOR; // cteni senzoru na caru
line |= LSENSOR << 1;
if (line!=0) break;
Delay_ms(1);
}
STOPR; STOPL;
 
movement=R;
cikcak();
cihla=T_DIRA;
dira=0;
}
///////////////////////////////////////////////////////////////////////////////
void prejeddiru() // vyresi diru
{
unsigned int16 n;
 
STOPL;STOPR;
beep(800,500);
switch (movement) //vrat se zpet na caru
{
case L:
for (n=COUVANI;n>0;n--) {GO(R,B,speed); Delay_ms(1);}
STOPL;STOPR;
break;
case R:
for (n=COUVANI;n>0;n--) {GO(L,B,speed); Delay_ms(1);}
STOPL;STOPR;
break;
case S:
goto sem;
break;
}
beep(800,500);
FR;FL; Delay_ms(PRES_DIRU); // popojedem dopredu mozna tam bude cara
sem:
STOPL; STOPR;
movement=S;
cikcak(); // najdi caru
cihla=T_DIRA;
dira=0;
}
///////////////////////////////////////////////////////////////////////////////
void main()
{
unsigned int16 n; // pro FOR
 
STOPL; STOPR; // prepne vystupy na ovladani motoru na output a zastavi
 
setup_oscillator(OSC_4MHZ|OSC_INTRC); // 4 MHz interni RC oscilator
 
port_b_pullups(TRUE); // pullups pro piano na diagnostiku
setup_spi(FALSE);
setup_timer_0(RTCC_INTERNAL|RTCC_DIV_1); // Casovac pro PWM
 
setup_timer_2(T2_DIV_BY_4,255,10); // Casovac pro regulaci
// preruseni kazdych 10ms
setup_adc_ports(sAN2|VSS_VDD); // nastaveni A/D prevodniku pro naraznik
setup_adc(ADC_CLOCK_INTERNAL);
set_adc_channel(2);
setup_timer_1(T1_INTERNAL|T1_DIV_BY_1); // Casovac pro naraznik
setup_ccp1(CCP_COMPARE_RESET_TIMER);
CCP_1=(2^10)-1; // prevod kazdou 1ms
 
setup_comparator(A0_VR_A1_VR); // inicializace komparatoru pro cidla cary
setup_vref(VREF_HIGH|TRESHOLD); // 32 kroku od 0.25 do 0.75 Vdd
 
Beep(1000,200); //double beep
Delay_ms(50);
Beep(1000,200);
Delay_ms(1000); // 1s
 
// povoleni rizeni rychlosti zataceni pres preruseni
enable_interrupts(INT_TIMER2);
enable_interrupts(GLOBAL);
 
/*---------------------------------------------------------------------------*/
sensors=S;
line=S;
last=S;
movement=S;
speed=FW_POMALU;
 
diagnostika();
cikcak(); // toc se, abys nasel caru
Delay_ms(500);
Beep(1000,200);
Delay_ms(500);
 
while(true) // hlavni smycka (jizda podle cary)
{
sensors = RSENSOR; // cteni senzoru na caru
sensors |= LSENSOR << 1;
 
if ((read_adc(ADC_READ_ONLY)<BUMPER_TRESHOLD) && (cihla==0)) objizdka();
 
switch (sensors) // zatacej podle toho, kde vidis caru
{
case S: // rovne
FL; FR; // pokud se jede dlouho rovne, tak pridej
dira=0;
movement=S;
continue;
case L: // trochu vlevo
GO(L, F, FW_POMALU+rovinka); GO(R, F, FW_STREDNE+rovinka);
line=L;
dira=0;
movement=L;
continue;
case R: // trochu vpravo
GO(R, F, FW_POMALU+rovinka); GO(L, F, FW_STREDNE+rovinka);
line=R;
dira=0;
movement=R;
continue;
default: // kdyz jsou obe cidla mimo caru, tak pokracuj dal
}
rovinka=0;
if (dira>=T_DIRA) prejeddiru();
if (last!=line) // pokud si prejel caru z jedne strany na druhou stranu, tak zabrzdi
{
last=line;
speed=FW_ZATACKA;
}
if (L==line) // kdyz jsou obe cidla mimo caru, zatoc na caru
{
STOPL;
GO(R, F, speed);
movement=L;
}
else
{
STOPR;
GO(L, F, speed);
movement=R;
}
} // while(true)
}
 
/roboti/istrobot/merkur/dokumentace/obrazky/PIC16F88/tank.HEX
0,0 → 1,271
:1000000008308A0000280000FF00030E8301A100D1
:100010007F08A0000A08A8008A01A00E0408A20018
:100020007708A3007808A4007908A5007A08A6003C
:100030007B08A700831383128C308400801C222845
:100040008C183528220884002308F7002408F800BB
:100050002508F9002608FA002708FB0028088A006E
:10006000210E8300FF0E7F0E09008A1149280A1015
:100070008A100A1182074C343A342034253455341E
:100080002034203452343A3420342534553400346A
:100090000034420F4C284E280130C20743080E3C62
:1000A0000318C30A4608553C0318C60AC708031DAF
:1000B000C7038C108A11222812308316A402031C55
:1000C0006F28A4308400FC3080050310800C800C65
:1000D000000803196F286D280000800B6C2883121C
:1000E000003483162108A3002008A200A208031DE3
:1000F0007C28A30803199B28051383120517831670
:100100008513831285137C088316A40083125C2058
:10011000831685138312851783160513831205131F
:100120007C088316A40083125C208316220803191E
:10013000A303A2037628831200347D3084000008D4
:100140000319B1280130F800F701F70BA528F80BC7
:10015000A4284A30F700F70BAB2800000000800B02
:10016000A228003470088400831620088000840AC6
:100170008001F00A8312003483162108F80120025E
:100180000318C5282008F700D128F7010830A2007D
:10019000A00DF70D210877020318F700F80DA20B48
:1001A000C828831200347E13FE127D088316A00037
:1001B0006430A1008312BC207708FD007808031D7D
:1001C0000129FE1A0129FE1913297E1BED287E182C
:1001D000ED287E19ED28FE1B13297E1CF928FE1B35
:1001E00013297E1BF9287E1813297E19F928FE1B76
:1001F000132920307E1E30308316A0008312B220D7
:100200001329FE16FE1F0D2978088000F8002D30F6
:100210008316A0008312B220FE13303078078316B5
:10022000A0008312B2207E1B20297D088316A00027
:100230000A30A1008312BC207708FD007E17DE285B
:10024000FE1F27292D308316A0008312B2203030E4
:100250007D078316A0008312B2200034BC01391C34
:1002600033293910342939140034391C6029831694
:100270008511831285154930F700F70B3D290000E1
:10028000000083168511831285114930F700F70BA2
:100290004729000000008316851183128515493017
:1002A000F700F70B51290000000083168511831217
:1002B00085111930F700F70B5B2900000000722947
:1002C00083168511831285158930F700F70B66298F
:1002D00083168511831285117230F700F70B6E2992
:1002E0000000000000348316A0012008073C031C16
:1002F000CF297E080139A1008312BE080319822983
:100300000030832901308316A2008312BD0803192F
:100310008B2900308C29013083162205003A0319FD
:10032000A4292108A20003108312BB0CBA0C0308F5
:10033000013983162206013C031DA429843083124F
:10034000BB060830BA068316A108031DAB29831229
:100350002E21C72983168312BD080319BC0ABD08C4
:100360000319B4290030B52901308316A200831285
:100370003C08053C0319BE290030BF290130831613
:100380002205003A0319C829831235212E2183162C
:10039000831235210310FE0C8316A00A75298312DF
:1003A0000034831686158312861D022B0130F4005B
:1003B000F430F3007408033C031CF429031DE42902
:1003C00073081F3C031CF4297408FD007308FC002B
:1003D00074088316A1007308A00083127120643092
:1003E000F3070318F40ADA290430FC00FA30FD00A0
:1003F0009D20FC0BF6298316061383120613831621
:10040000861383128613831606128312061283162E
:100410008612831286128316861283128612831620
:100420000612831206160430FC00FA30FD009D20EF
:10043000FC0B152A831606128312061283168612E7
:10044000831286120430FC00FA30FD009D20FC0B64
:10045000242A83160612831206128316861283122A
:1004600086160430FC00FA30FD009D20FC0B332A78
:1004700083160612831206128316861283128612C0
:100480000430FC00FA30FD009D20FC0B422A0330B2
:10049000FD007030FC008316A1016430A0008312BF
:1004A00071200430FC00FA30FD009D20FC0B532A23
:1004B0008316861383128613831606138312061778
:1004C0000430FC00FA30FD009D20FC0B622A8316EC
:1004D00006138312061383168613831286130430C1
:1004E000FC00FA30FD009D20FC0B712A83160613D8
:1004F0008312061383168613831286170430FC00BA
:10050000FA30FD009D20FC0B802A8316061383120F
:10051000061383168613831286130430FC00FA3008
:10052000FD009D20FC0B8F2A0330FD007030FC0085
:100530008316A1016430A000831271200430FC00F6
:10054000FA30FD009D20FC0BA02A8316861383122F
:1005500086138316061383120617831686128312D8
:10056000861283160612831206160430FC00FA3037
:10057000FD009D20FC0BB72A831606138312061379
:1005800083168613831286138316061283120612AD
:1005900083168612831286120430FC00FA30FD00A6
:1005A0009D20FC0BCE2A8316061383120613831696
:1005B0008613831286178316061283120612831679
:1005C0008612831286160430FC00FA30FD009D204E
:1005D000FC0BE52A83160613831206138316861373
:1005E000831286138316061283120612831686124E
:1005F000831286120430FC00FA30FD009D20FC0BB3
:10060000FC2AD129831606158312061DC22B8316D8
:1006100005168312051A1A2B0430FD004C30FC001D
:100620008316A1016430A000831271203230FD00D6
:100630009D20072B003083169C1B0130FC007C0D95
:10064000F700F70DF70DF830F70583121F08C739CB
:1006500077049F000630F700F70B2C2B00001F15C6
:100660001F19302B1E08F600003083161C1B0130AA
:10067000FC007C0DF700F70DF70DF830F70583123D
:100680001F08C73977049F000630F700F70B462B89
:1006900000001F151F194A2B1E08F5004830F000F6
:1006A0004C308316A0008312B2203A308316A0008B
:1006B0008312B22020308316A0008312B220750866
:1006C000FD001830FE00D3200530FC007C083720E8
:1006D000FC0AF7008316A0008312B2200A307C02C5
:1006E000031D662B7608FD001830FE00D32048302D
:1006F000FC003910FF30BB00BA00BC010130BD0066
:10070000BE01BF013F08093C031C8B2B7E30FE005D
:100710007321BF0A822BBD01BF013F080F3C031CA0
:100720009A2B29303F0784000008FD00FE0073214A
:10073000BF0A8D2BBF017C08840000080319A92B78
:100740007C0884000008FD00FE007321FC0ABF0A3B
:100750009B2B0130BE00FF30BA06BB063A08FE00F4
:1007600073213B08FE007321BE010130BD007E30C5
:10077000FE0073210430FC00FA30FD009D20FC0BCC
:10078000BC2B022B8A15BA28C10183169C1FCB2BC8
:100790008312C10A831600301C1B0130F7000310BE
:1007A000F70D77088312C104C108031DB12CF601AF
:1007B000F5014508023A0319E42B033A0319F72B14
:1007C000023A03190A2C212C8316861383128613EE
:1007D0008316061383120617831606128312061257
:1007E00083168612831286160130C500212C8316CB
:1007F0008612831286128316061283120616831639
:10080000061383120613831686138312861702308B
:10081000C500212C831686138312861383160613B4
:100820008312061783160612831206128316861287
:10083000831286160130C5002730F6001030F5000F
:10084000212C003083169C1B0130FC0000301C1B47
:1008500001307C04003A031D6D2C7508203C031DFB
:10086000672C76084E3C031D672CF601F5018312B8
:100870004508023A0319402C033A0319532C662CFD
:1008800083168613831286138316061383120617A4
:100890008316061283120612831686128312861698
:1008A0000130C500662C83168612831286128316C9
:1008B0000612831206168316061383120613831676
:1008C0008613831286170230C500662C8316F50A3C
:1008D0000319F60A8312212C831683124508023A63
:1008E0000319762C033A0319892C9C2C8316861342
:1008F00083128613831606138312061783160612B5
:100900008312061283168612831286160130C500E2
:100910009C2C83168612831286128316061283126B
:100920000616831606138312061383168613831284
:1009300086170230C5009C2C3230FD009D208316A6
:1009400006138312061383168613831286138316E7
:100950000612831206128316861283128612033041
:10096000C100003483160613831206138316861300
:1009700083128617831606128312061283168612B6
:1009800083128616C830FD009D208316061283123E
:10099000061283168612831286128316061383129A
:1009A000061383168613831286130330FD008430EA
:1009B000FC0003308316A100E830A00083127120F0
:1009C0000330C500C4238316061283120612831651
:1009D0008612831286168316861383128613831655
:1009E000061383120617D730FD009D20831686124A
:1009F0008312861283160612831206168316861336
:100A00008312861383160613831206170330F5002C
:100A1000C830FD009D20F50B082D831606138312A8
:100A2000061383168613831286173230FD009D202D
:100A300083160613831206138316861383128613F6
:100A400083168612831286128316061283120616E6
:100A50000530F5006E30FD009D20F50B2A2D831624
:100A600086128312861283160612831206168316C6
:100A700086138312861383160613831206176430B7
:100A8000FD009D200230F4005830F300F308031DF0
:100A90004C2DF40803196B2DC10183169C1F532D97
:100AA0008312C10A831600301C1B0130F7000310AB
:100AB000F70D77088312C104C1080319632D323082
:100AC000FD009D206B2D0130FD009D207308031952
:100AD000F403F303462D83160612831206128316BF
:100AE0008612831286160230F4005830F300F308A1
:100AF000031D7D2DF4080319982DC10183169C1F39
:100B0000842D8312C10A831600301C1B0130F700AC
:100B10000310F70D77088312C104C108031D982D37
:100B20000130FD009D2073080319F403F303772DB2
:100B300083160612831206128316861283128612F9
:100B400083160613831206138316861383128613E5
:100B50000130C500C4235530C700C6018A15F728E7
:100B600083160613831206138316861383128613C5
:100B700083160612831206128316861283128612B9
:100B80000330FD002030FC0001308316A100F4305A
:100B9000A000831271204508023A0319D62D033AAA
:100BA00003190E2E023A0319462E482E0230F40085
:100BB0005830F300F308031DE02DF4080319FD2D50
:100BC00001084202031CED2D831606128312061241
:100BD0008316861283128616F52D8316061283124B
:100BE000061283168612831286120130FD009D20A4
:100BF00073080319F403F303DA2D83160613831223
:100C00000613831686138312861383160612831225
:100C100006128316861283128612482E0230F400C2
:100C20005830F300F308031D182EF4080319352E6D
:100C300001084202031C252E831606138312061395
:100C400083168613831286172D2E8316061383129E
:100C5000061383168613831286130130FD009D2030
:100C600073080319F403F303122E83160613831279
:100C700006138316861383128613831606128312B5
:100C800006128316861283128612482E662E482E6E
:100C90000330FD002030FC0001308316A100F43049
:100CA000A000831271208316861283128612831687
:100CB0000612831206168316861383128613831672
:100CC0000613831206179630FD009D208316061327
:100CD0008312061383168613831286138316061255
:100CE0008312061283168612831286120330C50001
:0C0CF000C4235530C700C6018A159029A6
:1010000084011F30830583161F129F121B0880392D
:101010009B0007309C001C0883120D136030831660
:101020008F0082308312A9009830AA00AB004030B4
:10103000AC00AD00AE006030AF008630B000B43020
:10104000B1006030B200A430B300B400B50061302C
:10105000B6000330B700F030B800F0018316061375
:1010600083120613831686138312861383160612C1
:10107000831206128316861283128612623083163A
:101080008F008113831294128316061186140612A0
:10109000003083129400831694000108C739083881
:1010A00081004830F800053883129200FF30831623
:1010B00092001F129F121B08803904389B001F13D7
:1010C00083121F179F1783169F1383121F1410304C
:1010D000F8001F08C73978049F00853090008316F8
:1010E00086150B3083129700960107309500023069
:1010F00083169C000508033885000330F700F70BC2
:101100007F281C0883120D138A3083169D0003303C
:10111000FD00E830FC00A101C830A0008A11831254
:1011200071208A153230FD008A119D208A15033006
:10113000FD00E830FC008316A101C830A0008A1130
:10114000831271208A150430F300FA30FD008A11F1
:101150009D208A15F30BA52883168C14C0308312AA
:101160008B040330C000C100C400C500E630C200DB
:101170008A11D1298A158A11C4238A150230F300F5
:10118000FA30FD008A119D208A15F30BC028033028
:10119000FD00E830FC008316A101C830A0008A11D0
:1011A000831271208A150230F300FA30FD008A1193
:1011B0009D208A15F30BD528C00183169C1FE328B8
:1011C0008312C00A831600301C1B0130F700031085
:1011D000F70D77088312C0041F19EC281E087F3C06
:1011E000031CF828C708031DF8288A11B22C8A1599
:1011F0004008033A03190329013A03191729033A4E
:10120000031950298929831686138312861383169E
:10121000061383120617831686128312861283160C
:10122000061283120616C6010330C500DC28010829
:10123000F300E63043077302031920290318292914
:1012400083168613831286138316061383120617DA
:10125000312983160613831206138316861383120D
:1012600086130108F300F0304307730203193A298B
:1012700003184329831686128312861283160612D8
:10128000831206164B298316061283120612831642
:101290008612831286120230C100C601C500DC2806
:1012A0000108F300E63043077302031959290318B4
:1012B00062298316861283128612831606128312FF
:1012C00006166A29831606128312061283168612E0
:1012D000831286120108F300F030430773020319EA
:1012E000732903187C2983168613831286138316A9
:1012F0000613831206178429831606138312061316
:1013000083168613831286130130C100C601C500FF
:10131000DC28C3014608543C031891298A11B02DDA
:101320008A1541084402031999294108C400C830AC
:10133000C2004108023C031DBD2983160613831217
:101340000613831686138312861301084202031CB8
:10135000B22983168612831286128316061283120E
:101360000616BA29831606128312061283168612EF
:10137000831286120230C500DC29831606128312FE
:101380000612831686128312861201084202031C7B
:10139000D2298316861383128613831606138312AB
:1013A0000617DA298316061383120613831686138B
:0C13B000831286130130C500DC286300A6
:04400E00383FFC3FFC
:00000001FF
;PIC16F88
/roboti/istrobot/merkur/dokumentace/obrazky/PIC16F88/tank.LST
0,0 → 1,2130
CCS PCM C Compiler, Version 3.221, 27853 26-IV-05 01:36
 
Filename: D:\KAKLIK\programy\PIC_C\roboti\merkur\PIC16F88\tank.LST
 
ROM used: 2140 words (52%)
Largest free fragment is 1570
RAM used: 89 (51%) at main() level
101 (58%) worst case
Stack: 4 worst case (3 in main + 1 for interrupts)
 
*
0000: MOVLW 08
0001: MOVWF 0A
0002: GOTO 000
0003: NOP
0004: MOVWF 7F
0005: SWAPF 03,W
0006: CLRF 03
0007: MOVWF 21
0008: MOVF 7F,W
0009: MOVWF 20
000A: MOVF 0A,W
000B: MOVWF 28
000C: CLRF 0A
000D: SWAPF 20,F
000E: MOVF 04,W
000F: MOVWF 22
0010: MOVF 77,W
0011: MOVWF 23
0012: MOVF 78,W
0013: MOVWF 24
0014: MOVF 79,W
0015: MOVWF 25
0016: MOVF 7A,W
0017: MOVWF 26
0018: MOVF 7B,W
0019: MOVWF 27
001A: BCF 03.7
001B: BCF 03.5
001C: MOVLW 8C
001D: MOVWF 04
001E: BTFSS 00.1
001F: GOTO 022
0020: BTFSC 0C.1
0021: GOTO 035
0022: MOVF 22,W
0023: MOVWF 04
0024: MOVF 23,W
0025: MOVWF 77
0026: MOVF 24,W
0027: MOVWF 78
0028: MOVF 25,W
0029: MOVWF 79
002A: MOVF 26,W
002B: MOVWF 7A
002C: MOVF 27,W
002D: MOVWF 7B
002E: MOVF 28,W
002F: MOVWF 0A
0030: SWAPF 21,W
0031: MOVWF 03
0032: SWAPF 7F,F
0033: SWAPF 7F,W
0034: RETFIE
0035: BCF 0A.3
0036: GOTO 049
.................... #include "tank.h"
.................... #include <16F88.h>
.................... //////// Standard Header file for the PIC16F88 device ////////////////
.................... #device PIC16F88
.................... #list
....................
.................... #device adc=8
.................... #fuses NOWDT,INTRC_IO, NOPUT, MCLR, NOBROWNOUT, NOLVP, NOCPD, NOWRT, NODEBUG, NOPROTECT, NOFCMEN, NOIESO
.................... #use delay(clock=4000000)
*
005C: MOVLW 12
005D: BSF 03.5
005E: SUBWF 24,F
005F: BTFSS 03.0
0060: GOTO 06F
0061: MOVLW A4
0062: MOVWF 04
0063: MOVLW FC
0064: ANDWF 00,F
0065: BCF 03.0
0066: RRF 00,F
0067: RRF 00,F
0068: MOVF 00,W
0069: BTFSC 03.2
006A: GOTO 06F
006B: GOTO 06D
006C: NOP
006D: DECFSZ 00,F
006E: GOTO 06C
006F: BCF 03.5
0070: RETLW 00
*
009D: MOVLW 7D
009E: MOVWF 04
009F: MOVF 00,W
00A0: BTFSC 03.2
00A1: GOTO 0B1
00A2: MOVLW 01
00A3: MOVWF 78
00A4: CLRF 77
00A5: DECFSZ 77,F
00A6: GOTO 0A5
00A7: DECFSZ 78,F
00A8: GOTO 0A4
00A9: MOVLW 4A
00AA: MOVWF 77
00AB: DECFSZ 77,F
00AC: GOTO 0AB
00AD: NOP
00AE: NOP
00AF: DECFSZ 00,F
00B0: GOTO 0A2
00B1: RETLW 00
....................
....................
....................
.................... #define DEBUG
....................
.................... #define TXo PIN_A3 // To the transmitter modulator
.................... #include "AX25.c" // podprogram pro prenos telemetrie
.................... #list
....................
....................
.................... unsigned int8 sensors; // pomocna promenna pro cteni cidel na caru
.................... unsigned int8 line; // na ktere strane byla detekovana cara
.................... unsigned int8 speed; // rychlost zataceni
.................... unsigned int8 rovinka; // pocitadlo pro zjisteni rovneho useku
.................... unsigned int8 last; // kde byla cara, kdyz byly minule cidla mimo
.................... unsigned int8 movement; // obsahuje aktualni smer zataceni
.................... unsigned int8 dira; // pocita dobu po kterou je ztracena cara
.................... unsigned int8 cihla; // urcuje za jak dlouho muze byt znova detekovana cihla
....................
.................... // Konstanty pro dynamiku pohybu
.................... #define T_DIRA 85 // po jakem case zataceni se detekuje dira
.................... #define INC_SPEED 1 // prirustek rychlosti v jednom kroku
.................... #define FW_POMALU 230 // trochu mimo caru vnitrni pas
.................... #define FW_ZATACKA 200 // rychlost vnejsiho kola pri zataceni
.................... #define FW_STREDNE 240 // trochu mimo caru vnejsi pas
.................... #define COUVANI 600 // couvnuti zpet na caru, po detekci diry
.................... #define PRES_DIRU 150
.................... #define MAX_ROVINKA (255-FW_STREDNE)
.................... #define TRESHOLD 10 // rozhodovaci uroven komparatoru, 0xF = 0.75*Vdd
.................... #define BUMPER_TRESHOLD 128
.................... #define CIK_CAK 20000
.................... #define T_CIHLA 100 // perioda detekce cihly
....................
.................... //motory //Napred vypnout potom zapnout!
.................... #define FR output_low(PIN_B5); output_high(PIN_B4) // Vpred
.................... #define FL output_low(PIN_B7); output_high(PIN_B6)
.................... #define BR output_low(PIN_B4); output_high(PIN_B5) // Vzad
.................... #define BL output_low(PIN_B6); output_high(PIN_B7)
.................... #define STOPR output_low(PIN_B4);output_low(PIN_B5) // Zastav
.................... #define STOPL output_low(PIN_B6);output_low(PIN_B7)
....................
.................... #define L 0b10 // left
.................... #define R 0b01 // right
.................... #define S 0b11 // straight
....................
.................... //cidla
.................... #define RSENSOR C2OUT // Senzory na caru
.................... #define LSENSOR C1OUT
.................... #define BUMPER PIN_A4 // Senzor na cihlu
....................
.................... #define DIAG_SERVO PIN_B3 // Propojka pro diagnosticky mod
.................... #define DIAG_SENSORS PIN_B2 // Propojka pro diagnosticky mod
....................
.................... #DEFINE SOUND_HI PIN_A6 // komplementarni vystupy pro piezo pipak
.................... #DEFINE SOUND_LO PIN_A7
....................
.................... char AXstring[40]; // Buffer pro prenos telemetrie
....................
.................... // makro pro PWM
.................... #define GO(motor, direction, power) if(get_timer0()<=power) \
.................... {direction##motor;} else {stop##motor;}
....................
.................... #int_TIMER2
.................... void TIMER2_isr()
.................... {
.................... if (speed<255) speed+=INC_SPEED;
*
0049: INCFSZ 42,W
004A: GOTO 04C
004B: GOTO 04E
004C: MOVLW 01
004D: ADDWF 42,F
.................... if (rovinka<MAX_ROVINKA) rovinka++;
004E: MOVF 43,W
004F: SUBLW 0E
0050: BTFSC 03.0
0051: INCF 43,F
.................... if (dira<=T_DIRA) dira++;
0052: MOVF 46,W
0053: SUBLW 55
0054: BTFSC 03.0
0055: INCF 46,F
.................... if (cihla>0) cihla--;
0056: MOVF 47,F
0057: BTFSS 03.2
0058: DECF 47,F
.................... }
.................... // Primitivni Pipani
0059: BCF 0C.1
005A: BCF 0A.3
005B: GOTO 022
.................... void beep(unsigned int16 period, unsigned int16 length)
.................... {
.................... unsigned int16 nn;
....................
.................... for(nn=length; nn>0; nn--)
*
0071: BSF 03.5
0072: MOVF 21,W
0073: MOVWF 23
0074: MOVF 20,W
0075: MOVWF 22
0076: MOVF 22,F
0077: BTFSS 03.2
0078: GOTO 07C
0079: MOVF 23,F
007A: BTFSC 03.2
007B: GOTO 09B
.................... {
.................... output_high(SOUND_HI);output_low(SOUND_LO);
007C: BCF 05.6
007D: BCF 03.5
007E: BSF 05.6
007F: BSF 03.5
0080: BCF 05.7
0081: BCF 03.5
0082: BCF 05.7
.................... delay_us(period);
0083: MOVF 7C,W
0084: BSF 03.5
0085: MOVWF 24
0086: BCF 03.5
0087: CALL 05C
.................... output_high(SOUND_LO);output_low(SOUND_HI);
0088: BSF 03.5
0089: BCF 05.7
008A: BCF 03.5
008B: BSF 05.7
008C: BSF 03.5
008D: BCF 05.6
008E: BCF 03.5
008F: BCF 05.6
.................... delay_us(period);
0090: MOVF 7C,W
0091: BSF 03.5
0092: MOVWF 24
0093: BCF 03.5
0094: CALL 05C
.................... }
0095: BSF 03.5
0096: MOVF 22,W
0097: BTFSC 03.2
0098: DECF 23,F
0099: DECF 22,F
009A: GOTO 076
.................... }
009B: BCF 03.5
009C: RETLW 00
.................... /******************************************************************************/
.................... void diagnostika()
.................... {
.................... unsigned int16 n;
....................
.................... while (input(DIAG_SERVO)) // Propojka, ktera spousti diagnostiku
.................... {
*
01D1: BSF 03.5
01D2: BSF 06.3
01D3: BCF 03.5
01D4: BTFSS 06.3
01D5: GOTO 302
.................... for (n=500; n<800; n+=100)
01D6: MOVLW 01
01D7: MOVWF 74
01D8: MOVLW F4
01D9: MOVWF 73
01DA: MOVF 74,W
01DB: SUBLW 03
01DC: BTFSS 03.0
01DD: GOTO 1F4
01DE: BTFSS 03.2
01DF: GOTO 1E4
01E0: MOVF 73,W
01E1: SUBLW 1F
01E2: BTFSS 03.0
01E3: GOTO 1F4
.................... {
.................... beep(n,n); //beep UP
01E4: MOVF 74,W
01E5: MOVWF 7D
01E6: MOVF 73,W
01E7: MOVWF 7C
01E8: MOVF 74,W
01E9: BSF 03.5
01EA: MOVWF 21
01EB: MOVF 73,W
01EC: MOVWF 20
01ED: BCF 03.5
01EE: CALL 071
.................... };
01EF: MOVLW 64
01F0: ADDWF 73,F
01F1: BTFSC 03.0
01F2: INCF 74,F
01F3: GOTO 1DA
.................... Delay_ms(1000);
01F4: MOVLW 04
01F5: MOVWF 7C
01F6: MOVLW FA
01F7: MOVWF 7D
01F8: CALL 09D
01F9: DECFSZ 7C,F
01FA: GOTO 1F6
.................... //zastav vse
.................... STOPL; STOPR;
01FB: BSF 03.5
01FC: BCF 06.6
01FD: BCF 03.5
01FE: BCF 06.6
01FF: BSF 03.5
0200: BCF 06.7
0201: BCF 03.5
0202: BCF 06.7
0203: BSF 03.5
0204: BCF 06.4
0205: BCF 03.5
0206: BCF 06.4
0207: BSF 03.5
0208: BCF 06.5
0209: BCF 03.5
020A: BCF 06.5
.................... //pravy pas
.................... FR; Delay_ms(1000); STOPR; Delay_ms(1000);
020B: BSF 03.5
020C: BCF 06.5
020D: BCF 03.5
020E: BCF 06.5
020F: BSF 03.5
0210: BCF 06.4
0211: BCF 03.5
0212: BSF 06.4
0213: MOVLW 04
0214: MOVWF 7C
0215: MOVLW FA
0216: MOVWF 7D
0217: CALL 09D
0218: DECFSZ 7C,F
0219: GOTO 215
021A: BSF 03.5
021B: BCF 06.4
021C: BCF 03.5
021D: BCF 06.4
021E: BSF 03.5
021F: BCF 06.5
0220: BCF 03.5
0221: BCF 06.5
0222: MOVLW 04
0223: MOVWF 7C
0224: MOVLW FA
0225: MOVWF 7D
0226: CALL 09D
0227: DECFSZ 7C,F
0228: GOTO 224
.................... BR; Delay_ms(1000); STOPR; Delay_ms(1000);
0229: BSF 03.5
022A: BCF 06.4
022B: BCF 03.5
022C: BCF 06.4
022D: BSF 03.5
022E: BCF 06.5
022F: BCF 03.5
0230: BSF 06.5
0231: MOVLW 04
0232: MOVWF 7C
0233: MOVLW FA
0234: MOVWF 7D
0235: CALL 09D
0236: DECFSZ 7C,F
0237: GOTO 233
0238: BSF 03.5
0239: BCF 06.4
023A: BCF 03.5
023B: BCF 06.4
023C: BSF 03.5
023D: BCF 06.5
023E: BCF 03.5
023F: BCF 06.5
0240: MOVLW 04
0241: MOVWF 7C
0242: MOVLW FA
0243: MOVWF 7D
0244: CALL 09D
0245: DECFSZ 7C,F
0246: GOTO 242
.................... Beep(880,100); Delay_ms(1000);
0247: MOVLW 03
0248: MOVWF 7D
0249: MOVLW 70
024A: MOVWF 7C
024B: BSF 03.5
024C: CLRF 21
024D: MOVLW 64
024E: MOVWF 20
024F: BCF 03.5
0250: CALL 071
0251: MOVLW 04
0252: MOVWF 7C
0253: MOVLW FA
0254: MOVWF 7D
0255: CALL 09D
0256: DECFSZ 7C,F
0257: GOTO 253
.................... //levy pas
.................... FL; Delay_ms(1000); STOPL; Delay_ms(1000);
0258: BSF 03.5
0259: BCF 06.7
025A: BCF 03.5
025B: BCF 06.7
025C: BSF 03.5
025D: BCF 06.6
025E: BCF 03.5
025F: BSF 06.6
0260: MOVLW 04
0261: MOVWF 7C
0262: MOVLW FA
0263: MOVWF 7D
0264: CALL 09D
0265: DECFSZ 7C,F
0266: GOTO 262
0267: BSF 03.5
0268: BCF 06.6
0269: BCF 03.5
026A: BCF 06.6
026B: BSF 03.5
026C: BCF 06.7
026D: BCF 03.5
026E: BCF 06.7
026F: MOVLW 04
0270: MOVWF 7C
0271: MOVLW FA
0272: MOVWF 7D
0273: CALL 09D
0274: DECFSZ 7C,F
0275: GOTO 271
.................... BL; Delay_ms(1000); STOPL; Delay_ms(1000);
0276: BSF 03.5
0277: BCF 06.6
0278: BCF 03.5
0279: BCF 06.6
027A: BSF 03.5
027B: BCF 06.7
027C: BCF 03.5
027D: BSF 06.7
027E: MOVLW 04
027F: MOVWF 7C
0280: MOVLW FA
0281: MOVWF 7D
0282: CALL 09D
0283: DECFSZ 7C,F
0284: GOTO 280
0285: BSF 03.5
0286: BCF 06.6
0287: BCF 03.5
0288: BCF 06.6
0289: BSF 03.5
028A: BCF 06.7
028B: BCF 03.5
028C: BCF 06.7
028D: MOVLW 04
028E: MOVWF 7C
028F: MOVLW FA
0290: MOVWF 7D
0291: CALL 09D
0292: DECFSZ 7C,F
0293: GOTO 28F
.................... Beep(880,100); Delay_ms(1000);
0294: MOVLW 03
0295: MOVWF 7D
0296: MOVLW 70
0297: MOVWF 7C
0298: BSF 03.5
0299: CLRF 21
029A: MOVLW 64
029B: MOVWF 20
029C: BCF 03.5
029D: CALL 071
029E: MOVLW 04
029F: MOVWF 7C
02A0: MOVLW FA
02A1: MOVWF 7D
02A2: CALL 09D
02A3: DECFSZ 7C,F
02A4: GOTO 2A0
.................... //oba pasy
.................... FL; FR; Delay_ms(1000); STOPL; STOPR; Delay_ms(1000);
02A5: BSF 03.5
02A6: BCF 06.7
02A7: BCF 03.5
02A8: BCF 06.7
02A9: BSF 03.5
02AA: BCF 06.6
02AB: BCF 03.5
02AC: BSF 06.6
02AD: BSF 03.5
02AE: BCF 06.5
02AF: BCF 03.5
02B0: BCF 06.5
02B1: BSF 03.5
02B2: BCF 06.4
02B3: BCF 03.5
02B4: BSF 06.4
02B5: MOVLW 04
02B6: MOVWF 7C
02B7: MOVLW FA
02B8: MOVWF 7D
02B9: CALL 09D
02BA: DECFSZ 7C,F
02BB: GOTO 2B7
02BC: BSF 03.5
02BD: BCF 06.6
02BE: BCF 03.5
02BF: BCF 06.6
02C0: BSF 03.5
02C1: BCF 06.7
02C2: BCF 03.5
02C3: BCF 06.7
02C4: BSF 03.5
02C5: BCF 06.4
02C6: BCF 03.5
02C7: BCF 06.4
02C8: BSF 03.5
02C9: BCF 06.5
02CA: BCF 03.5
02CB: BCF 06.5
02CC: MOVLW 04
02CD: MOVWF 7C
02CE: MOVLW FA
02CF: MOVWF 7D
02D0: CALL 09D
02D1: DECFSZ 7C,F
02D2: GOTO 2CE
.................... BL; BR; Delay_ms(1000); STOPL; STOPR; Delay_ms(1000);
02D3: BSF 03.5
02D4: BCF 06.6
02D5: BCF 03.5
02D6: BCF 06.6
02D7: BSF 03.5
02D8: BCF 06.7
02D9: BCF 03.5
02DA: BSF 06.7
02DB: BSF 03.5
02DC: BCF 06.4
02DD: BCF 03.5
02DE: BCF 06.4
02DF: BSF 03.5
02E0: BCF 06.5
02E1: BCF 03.5
02E2: BSF 06.5
02E3: MOVLW 04
02E4: MOVWF 7C
02E5: MOVLW FA
02E6: MOVWF 7D
02E7: CALL 09D
02E8: DECFSZ 7C,F
02E9: GOTO 2E5
02EA: BSF 03.5
02EB: BCF 06.6
02EC: BCF 03.5
02ED: BCF 06.6
02EE: BSF 03.5
02EF: BCF 06.7
02F0: BCF 03.5
02F1: BCF 06.7
02F2: BSF 03.5
02F3: BCF 06.4
02F4: BCF 03.5
02F5: BCF 06.4
02F6: BSF 03.5
02F7: BCF 06.5
02F8: BCF 03.5
02F9: BCF 06.5
02FA: MOVLW 04
02FB: MOVWF 7C
02FC: MOVLW FA
02FD: MOVWF 7D
02FE: CALL 09D
02FF: DECFSZ 7C,F
0300: GOTO 2FC
.................... };
0301: GOTO 1D1
.................... while (input(DIAG_SENSORS))
.................... {
0302: BSF 03.5
0303: BSF 06.2
0304: BCF 03.5
0305: BTFSS 06.2
0306: GOTO 3C2
.................... int ls, rs;
.................... while(!input(BUMPER)){beep(1100,100); Delay_ms(50);}
0307: BSF 03.5
0308: BSF 05.4
0309: BCF 03.5
030A: BTFSC 05.4
030B: GOTO 31A
030C: MOVLW 04
030D: MOVWF 7D
030E: MOVLW 4C
030F: MOVWF 7C
0310: BSF 03.5
0311: CLRF 21
0312: MOVLW 64
0313: MOVWF 20
0314: BCF 03.5
0315: CALL 071
0316: MOVLW 32
0317: MOVWF 7D
0318: CALL 09D
0319: GOTO 307
.................... set_adc_channel(RSENSOR);
031A: MOVLW 00
031B: BSF 03.5
031C: BTFSC 1C.7
031D: MOVLW 01
031E: MOVWF 7C
031F: RLF 7C,W
0320: MOVWF 77
0321: RLF 77,F
0322: RLF 77,F
0323: MOVLW F8
0324: ANDWF 77,F
0325: BCF 03.5
0326: MOVF 1F,W
0327: ANDLW C7
0328: IORWF 77,W
0329: MOVWF 1F
.................... Delay_us(20);
032A: MOVLW 06
032B: MOVWF 77
032C: DECFSZ 77,F
032D: GOTO 32C
032E: NOP
.................... rs=read_adc();
032F: BSF 1F.2
0330: BTFSC 1F.2
0331: GOTO 330
0332: MOVF 1E,W
0333: MOVWF 76
.................... set_adc_channel(LSENSOR);
0334: MOVLW 00
0335: BSF 03.5
0336: BTFSC 1C.6
0337: MOVLW 01
0338: MOVWF 7C
0339: RLF 7C,W
033A: MOVWF 77
033B: RLF 77,F
033C: RLF 77,F
033D: MOVLW F8
033E: ANDWF 77,F
033F: BCF 03.5
0340: MOVF 1F,W
0341: ANDLW C7
0342: IORWF 77,W
0343: MOVWF 1F
.................... Delay_us(20);
0344: MOVLW 06
0345: MOVWF 77
0346: DECFSZ 77,F
0347: GOTO 346
0348: NOP
.................... ls=read_adc();
0349: BSF 1F.2
034A: BTFSC 1F.2
034B: GOTO 34A
034C: MOVF 1E,W
034D: MOVWF 75
.................... sprintf(AXstring,"L: %U R: %U\0", ls, rs); // Convert DATA to String.
034E: MOVLW 48
034F: MOVWF 70
0350: MOVLW 4C
0351: BSF 03.5
0352: MOVWF 20
0353: BCF 03.5
0354: CALL 0B2
0355: MOVLW 3A
0356: BSF 03.5
0357: MOVWF 20
0358: BCF 03.5
0359: CALL 0B2
035A: MOVLW 20
035B: BSF 03.5
035C: MOVWF 20
035D: BCF 03.5
035E: CALL 0B2
035F: MOVF 75,W
0360: MOVWF 7D
0361: MOVLW 18
0362: MOVWF 7E
0363: CALL 0D3
0364: MOVLW 05
0365: MOVWF 7C
0366: MOVF 7C,W
0367: CALL 037
0368: INCF 7C,F
0369: MOVWF 77
036A: BSF 03.5
036B: MOVWF 20
036C: BCF 03.5
036D: CALL 0B2
036E: MOVLW 0A
036F: SUBWF 7C,W
0370: BTFSS 03.2
0371: GOTO 366
0372: MOVF 76,W
0373: MOVWF 7D
0374: MOVLW 18
0375: MOVWF 7E
0376: CALL 0D3
*
082D: CLRF 70
.................... SendPacket(&AXstring[0]);
*
0377: MOVLW 48
0378: MOVWF 7C
.................... delay_ms(1000);
*
03BA: MOVLW 04
03BB: MOVWF 7C
03BC: MOVLW FA
03BD: MOVWF 7D
03BE: CALL 09D
03BF: DECFSZ 7C,F
03C0: GOTO 3BC
.................... };
03C1: GOTO 302
.................... }
03C2: BSF 0A.3
03C3: GOTO 0BA (RETURN)
.................... ///////////////////////////////////////////////////////////////////////////////
.................... void cikcak()
.................... {
.................... unsigned int16 n;
....................
.................... line = RSENSOR; // cteni senzoru na caru
03C4: CLRF 41
03C5: BSF 03.5
03C6: BTFSS 1C.7
03C7: GOTO 3CB
03C8: BCF 03.5
03C9: INCF 41,F
03CA: BSF 03.5
.................... line |= LSENSOR << 1;
03CB: MOVLW 00
03CC: BTFSC 1C.6
03CD: MOVLW 01
03CE: MOVWF 77
03CF: BCF 03.0
03D0: RLF 77,F
03D1: MOVF 77,W
03D2: BCF 03.5
03D3: IORWF 41,F
.................... if (line!=0) return;
03D4: MOVF 41,F
03D5: BTFSS 03.2
03D6: GOTO 4B1
....................
.................... n=0;
03D7: CLRF 76
03D8: CLRF 75
.................... switch(movement) // podivej se na druhou stranu nez se jelo
.................... {
03D9: MOVF 45,W
03DA: XORLW 02
03DB: BTFSC 03.2
03DC: GOTO 3E4
03DD: XORLW 03
03DE: BTFSC 03.2
03DF: GOTO 3F7
03E0: XORLW 02
03E1: BTFSC 03.2
03E2: GOTO 40A
03E3: GOTO 421
.................... case L:
.................... FL;BR;
03E4: BSF 03.5
03E5: BCF 06.7
03E6: BCF 03.5
03E7: BCF 06.7
03E8: BSF 03.5
03E9: BCF 06.6
03EA: BCF 03.5
03EB: BSF 06.6
03EC: BSF 03.5
03ED: BCF 06.4
03EE: BCF 03.5
03EF: BCF 06.4
03F0: BSF 03.5
03F1: BCF 06.5
03F2: BCF 03.5
03F3: BSF 06.5
.................... movement=R;
03F4: MOVLW 01
03F5: MOVWF 45
.................... break;
03F6: GOTO 421
.................... case R:
.................... FR;BL;
03F7: BSF 03.5
03F8: BCF 06.5
03F9: BCF 03.5
03FA: BCF 06.5
03FB: BSF 03.5
03FC: BCF 06.4
03FD: BCF 03.5
03FE: BSF 06.4
03FF: BSF 03.5
0400: BCF 06.6
0401: BCF 03.5
0402: BCF 06.6
0403: BSF 03.5
0404: BCF 06.7
0405: BCF 03.5
0406: BSF 06.7
.................... movement=L;
0407: MOVLW 02
0408: MOVWF 45
.................... break;
0409: GOTO 421
.................... case S:
.................... FL;BR;
040A: BSF 03.5
040B: BCF 06.7
040C: BCF 03.5
040D: BCF 06.7
040E: BSF 03.5
040F: BCF 06.6
0410: BCF 03.5
0411: BSF 06.6
0412: BSF 03.5
0413: BCF 06.4
0414: BCF 03.5
0415: BCF 06.4
0416: BSF 03.5
0417: BCF 06.5
0418: BCF 03.5
0419: BSF 06.5
.................... movement=R;
041A: MOVLW 01
041B: MOVWF 45
.................... n=CIK_CAK/2;
041C: MOVLW 27
041D: MOVWF 76
041E: MOVLW 10
041F: MOVWF 75
.................... break;
0420: GOTO 421
.................... }
.................... while (0==(RSENSOR|LSENSOR)) // zkontroluj caru
.................... {
0421: MOVLW 00
0422: BSF 03.5
0423: BTFSC 1C.7
0424: MOVLW 01
0425: MOVWF 7C
0426: MOVLW 00
0427: BTFSC 1C.6
0428: MOVLW 01
0429: IORWF 7C,W
042A: XORLW 00
042B: BTFSS 03.2
042C: GOTO 46D
.................... if (n==CIK_CAK) // zmen smer zataceni
042D: MOVF 75,W
042E: SUBLW 20
042F: BTFSS 03.2
0430: GOTO 467
0431: MOVF 76,W
0432: SUBLW 4E
0433: BTFSS 03.2
0434: GOTO 467
.................... {
.................... n=0;
0435: CLRF 76
0436: CLRF 75
.................... switch(movement)
.................... {
0437: BCF 03.5
0438: MOVF 45,W
0439: XORLW 02
043A: BTFSC 03.2
043B: GOTO 440
043C: XORLW 03
043D: BTFSC 03.2
043E: GOTO 453
043F: GOTO 466
.................... case L:
.................... FL;BR;
0440: BSF 03.5
0441: BCF 06.7
0442: BCF 03.5
0443: BCF 06.7
0444: BSF 03.5
0445: BCF 06.6
0446: BCF 03.5
0447: BSF 06.6
0448: BSF 03.5
0449: BCF 06.4
044A: BCF 03.5
044B: BCF 06.4
044C: BSF 03.5
044D: BCF 06.5
044E: BCF 03.5
044F: BSF 06.5
.................... movement=R;
0450: MOVLW 01
0451: MOVWF 45
.................... break;
0452: GOTO 466
.................... case R:
.................... FR;BL;
0453: BSF 03.5
0454: BCF 06.5
0455: BCF 03.5
0456: BCF 06.5
0457: BSF 03.5
0458: BCF 06.4
0459: BCF 03.5
045A: BSF 06.4
045B: BSF 03.5
045C: BCF 06.6
045D: BCF 03.5
045E: BCF 06.6
045F: BSF 03.5
0460: BCF 06.7
0461: BCF 03.5
0462: BSF 06.7
.................... movement=L;
0463: MOVLW 02
0464: MOVWF 45
.................... break;
0465: GOTO 466
0466: BSF 03.5
.................... }
.................... }
.................... n++;
0467: INCF 75,F
0468: BTFSC 03.2
0469: INCF 76,F
.................... }
046A: BCF 03.5
046B: GOTO 421
046C: BSF 03.5
.................... switch(movement)
.................... {
046D: BCF 03.5
046E: MOVF 45,W
046F: XORLW 02
0470: BTFSC 03.2
0471: GOTO 476
0472: XORLW 03
0473: BTFSC 03.2
0474: GOTO 489
0475: GOTO 49C
.................... case L:
.................... FL;BR;
0476: BSF 03.5
0477: BCF 06.7
0478: BCF 03.5
0479: BCF 06.7
047A: BSF 03.5
047B: BCF 06.6
047C: BCF 03.5
047D: BSF 06.6
047E: BSF 03.5
047F: BCF 06.4
0480: BCF 03.5
0481: BCF 06.4
0482: BSF 03.5
0483: BCF 06.5
0484: BCF 03.5
0485: BSF 06.5
.................... movement=R;
0486: MOVLW 01
0487: MOVWF 45
.................... break;
0488: GOTO 49C
.................... case R:
.................... FR;BL;
0489: BSF 03.5
048A: BCF 06.5
048B: BCF 03.5
048C: BCF 06.5
048D: BSF 03.5
048E: BCF 06.4
048F: BCF 03.5
0490: BSF 06.4
0491: BSF 03.5
0492: BCF 06.6
0493: BCF 03.5
0494: BCF 06.6
0495: BSF 03.5
0496: BCF 06.7
0497: BCF 03.5
0498: BSF 06.7
.................... movement=L;
0499: MOVLW 02
049A: MOVWF 45
.................... break;
049B: GOTO 49C
.................... }
.................... Delay_ms(50);
049C: MOVLW 32
049D: MOVWF 7D
049E: CALL 09D
.................... STOPL;STOPR; // nasli jsme caru
049F: BSF 03.5
04A0: BCF 06.6
04A1: BCF 03.5
04A2: BCF 06.6
04A3: BSF 03.5
04A4: BCF 06.7
04A5: BCF 03.5
04A6: BCF 06.7
04A7: BSF 03.5
04A8: BCF 06.4
04A9: BCF 03.5
04AA: BCF 06.4
04AB: BSF 03.5
04AC: BCF 06.5
04AD: BCF 03.5
04AE: BCF 06.5
.................... line=S;
04AF: MOVLW 03
04B0: MOVWF 41
.................... }
04B1: RETLW 00
.................... ///////////////////////////////////////////////////////////////////////////////
.................... void objizdka() // objede cihlu
.................... {
.................... unsigned int16 n;
....................
.................... BL;BR;Delay_ms(200);
04B2: BSF 03.5
04B3: BCF 06.6
04B4: BCF 03.5
04B5: BCF 06.6
04B6: BSF 03.5
04B7: BCF 06.7
04B8: BCF 03.5
04B9: BSF 06.7
04BA: BSF 03.5
04BB: BCF 06.4
04BC: BCF 03.5
04BD: BCF 06.4
04BE: BSF 03.5
04BF: BCF 06.5
04C0: BCF 03.5
04C1: BSF 06.5
04C2: MOVLW C8
04C3: MOVWF 7D
04C4: CALL 09D
.................... STOPR;STOPL;
04C5: BSF 03.5
04C6: BCF 06.4
04C7: BCF 03.5
04C8: BCF 06.4
04C9: BSF 03.5
04CA: BCF 06.5
04CB: BCF 03.5
04CC: BCF 06.5
04CD: BSF 03.5
04CE: BCF 06.6
04CF: BCF 03.5
04D0: BCF 06.6
04D1: BSF 03.5
04D2: BCF 06.7
04D3: BCF 03.5
04D4: BCF 06.7
.................... beep(900,1000);
04D5: MOVLW 03
04D6: MOVWF 7D
04D7: MOVLW 84
04D8: MOVWF 7C
04D9: MOVLW 03
04DA: BSF 03.5
04DB: MOVWF 21
04DC: MOVLW E8
04DD: MOVWF 20
04DE: BCF 03.5
04DF: CALL 071
.................... movement=S;
04E0: MOVLW 03
04E1: MOVWF 45
.................... cikcak();
04E2: CALL 3C4
....................
.................... BR; FL; Delay_ms(215); // otoc se 70° do prava
04E3: BSF 03.5
04E4: BCF 06.4
04E5: BCF 03.5
04E6: BCF 06.4
04E7: BSF 03.5
04E8: BCF 06.5
04E9: BCF 03.5
04EA: BSF 06.5
04EB: BSF 03.5
04EC: BCF 06.7
04ED: BCF 03.5
04EE: BCF 06.7
04EF: BSF 03.5
04F0: BCF 06.6
04F1: BCF 03.5
04F2: BSF 06.6
04F3: MOVLW D7
04F4: MOVWF 7D
04F5: CALL 09D
....................
.................... FR; FL; Delay_ms(600); // popojed rovne
04F6: BSF 03.5
04F7: BCF 06.5
04F8: BCF 03.5
04F9: BCF 06.5
04FA: BSF 03.5
04FB: BCF 06.4
04FC: BCF 03.5
04FD: BSF 06.4
04FE: BSF 03.5
04FF: BCF 06.7
0500: BCF 03.5
0501: BCF 06.7
0502: BSF 03.5
0503: BCF 06.6
0504: BCF 03.5
0505: BSF 06.6
0506: MOVLW 03
0507: MOVWF 75
0508: MOVLW C8
0509: MOVWF 7D
050A: CALL 09D
050B: DECFSZ 75,F
050C: GOTO 508
....................
.................... BL; Delay_ms(50); // otoc se 90° do leva
050D: BSF 03.5
050E: BCF 06.6
050F: BCF 03.5
0510: BCF 06.6
0511: BSF 03.5
0512: BCF 06.7
0513: BCF 03.5
0514: BSF 06.7
0515: MOVLW 32
0516: MOVWF 7D
0517: CALL 09D
.................... STOPL; FR; Delay_ms(550);
0518: BSF 03.5
0519: BCF 06.6
051A: BCF 03.5
051B: BCF 06.6
051C: BSF 03.5
051D: BCF 06.7
051E: BCF 03.5
051F: BCF 06.7
0520: BSF 03.5
0521: BCF 06.5
0522: BCF 03.5
0523: BCF 06.5
0524: BSF 03.5
0525: BCF 06.4
0526: BCF 03.5
0527: BSF 06.4
0528: MOVLW 05
0529: MOVWF 75
052A: MOVLW 6E
052B: MOVWF 7D
052C: CALL 09D
052D: DECFSZ 75,F
052E: GOTO 52A
....................
.................... FR; FL; Delay_ms(100); // popojed rovne na slepo
052F: BSF 03.5
0530: BCF 06.5
0531: BCF 03.5
0532: BCF 06.5
0533: BSF 03.5
0534: BCF 06.4
0535: BCF 03.5
0536: BSF 06.4
0537: BSF 03.5
0538: BCF 06.7
0539: BCF 03.5
053A: BCF 06.7
053B: BSF 03.5
053C: BCF 06.6
053D: BCF 03.5
053E: BSF 06.6
053F: MOVLW 64
0540: MOVWF 7D
0541: CALL 09D
.................... for(n=600;n>0;n--) // popojed rovne ale kontroluj caru
0542: MOVLW 02
0543: MOVWF 74
0544: MOVLW 58
0545: MOVWF 73
0546: MOVF 73,F
0547: BTFSS 03.2
0548: GOTO 54C
0549: MOVF 74,F
054A: BTFSC 03.2
054B: GOTO 56B
.................... {
.................... line = RSENSOR; // cteni senzoru na caru
054C: CLRF 41
054D: BSF 03.5
054E: BTFSS 1C.7
054F: GOTO 553
0550: BCF 03.5
0551: INCF 41,F
0552: BSF 03.5
.................... line |= LSENSOR << 1;
0553: MOVLW 00
0554: BTFSC 1C.6
0555: MOVLW 01
0556: MOVWF 77
0557: BCF 03.0
0558: RLF 77,F
0559: MOVF 77,W
055A: BCF 03.5
055B: IORWF 41,F
.................... if (line!=0) {Delay_ms(50); break;}
055C: MOVF 41,F
055D: BTFSC 03.2
055E: GOTO 563
055F: MOVLW 32
0560: MOVWF 7D
0561: CALL 09D
0562: GOTO 56B
.................... Delay_ms(1);
0563: MOVLW 01
0564: MOVWF 7D
0565: CALL 09D
.................... }
0566: MOVF 73,W
0567: BTFSC 03.2
0568: DECF 74,F
0569: DECF 73,F
056A: GOTO 546
....................
.................... BR; // otoc se 60° do prava
056B: BSF 03.5
056C: BCF 06.4
056D: BCF 03.5
056E: BCF 06.4
056F: BSF 03.5
0570: BCF 06.5
0571: BCF 03.5
0572: BSF 06.5
.................... for(n=600;n>0;n--)
0573: MOVLW 02
0574: MOVWF 74
0575: MOVLW 58
0576: MOVWF 73
0577: MOVF 73,F
0578: BTFSS 03.2
0579: GOTO 57D
057A: MOVF 74,F
057B: BTFSC 03.2
057C: GOTO 598
.................... {
.................... line = RSENSOR; // cteni senzoru na caru
057D: CLRF 41
057E: BSF 03.5
057F: BTFSS 1C.7
0580: GOTO 584
0581: BCF 03.5
0582: INCF 41,F
0583: BSF 03.5
.................... line |= LSENSOR << 1;
0584: MOVLW 00
0585: BTFSC 1C.6
0586: MOVLW 01
0587: MOVWF 77
0588: BCF 03.0
0589: RLF 77,F
058A: MOVF 77,W
058B: BCF 03.5
058C: IORWF 41,F
.................... if (line!=0) break;
058D: MOVF 41,F
058E: BTFSS 03.2
058F: GOTO 598
.................... Delay_ms(1);
0590: MOVLW 01
0591: MOVWF 7D
0592: CALL 09D
.................... }
0593: MOVF 73,W
0594: BTFSC 03.2
0595: DECF 74,F
0596: DECF 73,F
0597: GOTO 577
.................... STOPR; STOPL;
0598: BSF 03.5
0599: BCF 06.4
059A: BCF 03.5
059B: BCF 06.4
059C: BSF 03.5
059D: BCF 06.5
059E: BCF 03.5
059F: BCF 06.5
05A0: BSF 03.5
05A1: BCF 06.6
05A2: BCF 03.5
05A3: BCF 06.6
05A4: BSF 03.5
05A5: BCF 06.7
05A6: BCF 03.5
05A7: BCF 06.7
....................
.................... movement=R;
05A8: MOVLW 01
05A9: MOVWF 45
.................... cikcak();
05AA: CALL 3C4
.................... cihla=T_DIRA;
05AB: MOVLW 55
05AC: MOVWF 47
.................... dira=0;
05AD: CLRF 46
.................... }
05AE: BSF 0A.3
05AF: GOTO 0F7 (RETURN)
.................... ///////////////////////////////////////////////////////////////////////////////
.................... void prejeddiru() // vyresi diru
.................... {
.................... unsigned int16 n;
....................
.................... STOPL;STOPR;
05B0: BSF 03.5
05B1: BCF 06.6
05B2: BCF 03.5
05B3: BCF 06.6
05B4: BSF 03.5
05B5: BCF 06.7
05B6: BCF 03.5
05B7: BCF 06.7
05B8: BSF 03.5
05B9: BCF 06.4
05BA: BCF 03.5
05BB: BCF 06.4
05BC: BSF 03.5
05BD: BCF 06.5
05BE: BCF 03.5
05BF: BCF 06.5
.................... beep(800,500);
05C0: MOVLW 03
05C1: MOVWF 7D
05C2: MOVLW 20
05C3: MOVWF 7C
05C4: MOVLW 01
05C5: BSF 03.5
05C6: MOVWF 21
05C7: MOVLW F4
05C8: MOVWF 20
05C9: BCF 03.5
05CA: CALL 071
.................... switch (movement) //vrat se zpet na caru
.................... {
05CB: MOVF 45,W
05CC: XORLW 02
05CD: BTFSC 03.2
05CE: GOTO 5D6
05CF: XORLW 03
05D0: BTFSC 03.2
05D1: GOTO 60E
05D2: XORLW 02
05D3: BTFSC 03.2
05D4: GOTO 646
05D5: GOTO 648
.................... case L:
.................... for (n=COUVANI;n>0;n--) {GO(R,B,speed); Delay_ms(1);}
05D6: MOVLW 02
05D7: MOVWF 74
05D8: MOVLW 58
05D9: MOVWF 73
05DA: MOVF 73,F
05DB: BTFSS 03.2
05DC: GOTO 5E0
05DD: MOVF 74,F
05DE: BTFSC 03.2
05DF: GOTO 5FD
05E0: MOVF 01,W
05E1: SUBWF 42,W
05E2: BTFSS 03.0
05E3: GOTO 5ED
05E4: BSF 03.5
05E5: BCF 06.4
05E6: BCF 03.5
05E7: BCF 06.4
05E8: BSF 03.5
05E9: BCF 06.5
05EA: BCF 03.5
05EB: BSF 06.5
05EC: GOTO 5F5
05ED: BSF 03.5
05EE: BCF 06.4
05EF: BCF 03.5
05F0: BCF 06.4
05F1: BSF 03.5
05F2: BCF 06.5
05F3: BCF 03.5
05F4: BCF 06.5
05F5: MOVLW 01
05F6: MOVWF 7D
05F7: CALL 09D
05F8: MOVF 73,W
05F9: BTFSC 03.2
05FA: DECF 74,F
05FB: DECF 73,F
05FC: GOTO 5DA
.................... STOPL;STOPR;
05FD: BSF 03.5
05FE: BCF 06.6
05FF: BCF 03.5
0600: BCF 06.6
0601: BSF 03.5
0602: BCF 06.7
0603: BCF 03.5
0604: BCF 06.7
0605: BSF 03.5
0606: BCF 06.4
0607: BCF 03.5
0608: BCF 06.4
0609: BSF 03.5
060A: BCF 06.5
060B: BCF 03.5
060C: BCF 06.5
.................... break;
060D: GOTO 648
.................... case R:
.................... for (n=COUVANI;n>0;n--) {GO(L,B,speed); Delay_ms(1);}
060E: MOVLW 02
060F: MOVWF 74
0610: MOVLW 58
0611: MOVWF 73
0612: MOVF 73,F
0613: BTFSS 03.2
0614: GOTO 618
0615: MOVF 74,F
0616: BTFSC 03.2
0617: GOTO 635
0618: MOVF 01,W
0619: SUBWF 42,W
061A: BTFSS 03.0
061B: GOTO 625
061C: BSF 03.5
061D: BCF 06.6
061E: BCF 03.5
061F: BCF 06.6
0620: BSF 03.5
0621: BCF 06.7
0622: BCF 03.5
0623: BSF 06.7
0624: GOTO 62D
0625: BSF 03.5
0626: BCF 06.6
0627: BCF 03.5
0628: BCF 06.6
0629: BSF 03.5
062A: BCF 06.7
062B: BCF 03.5
062C: BCF 06.7
062D: MOVLW 01
062E: MOVWF 7D
062F: CALL 09D
0630: MOVF 73,W
0631: BTFSC 03.2
0632: DECF 74,F
0633: DECF 73,F
0634: GOTO 612
.................... STOPL;STOPR;
0635: BSF 03.5
0636: BCF 06.6
0637: BCF 03.5
0638: BCF 06.6
0639: BSF 03.5
063A: BCF 06.7
063B: BCF 03.5
063C: BCF 06.7
063D: BSF 03.5
063E: BCF 06.4
063F: BCF 03.5
0640: BCF 06.4
0641: BSF 03.5
0642: BCF 06.5
0643: BCF 03.5
0644: BCF 06.5
.................... break;
0645: GOTO 648
.................... case S:
.................... goto sem;
0646: GOTO 666
.................... break;
0647: GOTO 648
.................... }
.................... beep(800,500);
0648: MOVLW 03
0649: MOVWF 7D
064A: MOVLW 20
064B: MOVWF 7C
064C: MOVLW 01
064D: BSF 03.5
064E: MOVWF 21
064F: MOVLW F4
0650: MOVWF 20
0651: BCF 03.5
0652: CALL 071
.................... FR;FL; Delay_ms(PRES_DIRU); // popojedem dopredu mozna tam bude cara
0653: BSF 03.5
0654: BCF 06.5
0655: BCF 03.5
0656: BCF 06.5
0657: BSF 03.5
0658: BCF 06.4
0659: BCF 03.5
065A: BSF 06.4
065B: BSF 03.5
065C: BCF 06.7
065D: BCF 03.5
065E: BCF 06.7
065F: BSF 03.5
0660: BCF 06.6
0661: BCF 03.5
0662: BSF 06.6
0663: MOVLW 96
0664: MOVWF 7D
0665: CALL 09D
.................... sem:
.................... STOPL; STOPR;
0666: BSF 03.5
0667: BCF 06.6
0668: BCF 03.5
0669: BCF 06.6
066A: BSF 03.5
066B: BCF 06.7
066C: BCF 03.5
066D: BCF 06.7
066E: BSF 03.5
066F: BCF 06.4
0670: BCF 03.5
0671: BCF 06.4
0672: BSF 03.5
0673: BCF 06.5
0674: BCF 03.5
0675: BCF 06.5
.................... movement=S;
0676: MOVLW 03
0677: MOVWF 45
.................... cikcak(); // najdi caru
0678: CALL 3C4
.................... cihla=T_DIRA;
0679: MOVLW 55
067A: MOVWF 47
.................... dira=0;
067B: CLRF 46
.................... }
067C: BSF 0A.3
067D: GOTO 190 (RETURN)
.................... ///////////////////////////////////////////////////////////////////////////////
.................... void main()
.................... {
*
0800: CLRF 04
0801: MOVLW 1F
0802: ANDWF 03,F
0803: BSF 03.5
0804: BCF 1F.4
0805: BCF 1F.5
0806: MOVF 1B,W
0807: ANDLW 80
0808: MOVWF 1B
0809: MOVLW 07
080A: MOVWF 1C
080B: MOVF 1C,W
080C: BCF 03.5
080D: BCF 0D.6
080E: MOVLW 60
080F: BSF 03.5
0810: MOVWF 0F
.................... unsigned int16 n; // pro FOR
....................
.................... STOPL; STOPR; // prepne vystupy na ovladani motoru na output a zastavi
*
082E: BSF 03.5
082F: BCF 06.6
0830: BCF 03.5
0831: BCF 06.6
0832: BSF 03.5
0833: BCF 06.7
0834: BCF 03.5
0835: BCF 06.7
0836: BSF 03.5
0837: BCF 06.4
0838: BCF 03.5
0839: BCF 06.4
083A: BSF 03.5
083B: BCF 06.5
083C: BCF 03.5
083D: BCF 06.5
....................
.................... setup_oscillator(OSC_4MHZ|OSC_INTRC); // 4 MHz interni RC oscilator
083E: MOVLW 62
083F: BSF 03.5
0840: MOVWF 0F
....................
.................... port_b_pullups(TRUE); // pullups pro piano na diagnostiku
0841: BCF 01.7
.................... setup_spi(FALSE);
0842: BCF 03.5
0843: BCF 14.5
0844: BSF 03.5
0845: BCF 06.2
0846: BSF 06.1
0847: BCF 06.4
0848: MOVLW 00
0849: BCF 03.5
084A: MOVWF 14
084B: BSF 03.5
084C: MOVWF 14
.................... setup_timer_0(RTCC_INTERNAL|RTCC_DIV_1); // Casovac pro PWM
084D: MOVF 01,W
084E: ANDLW C7
084F: IORLW 08
0850: MOVWF 01
....................
.................... setup_timer_2(T2_DIV_BY_4,255,10); // Casovac pro regulaci
0851: MOVLW 48
0852: MOVWF 78
0853: IORLW 05
0854: BCF 03.5
0855: MOVWF 12
0856: MOVLW FF
0857: BSF 03.5
0858: MOVWF 12
.................... // preruseni kazdych 10ms
.................... setup_adc_ports(sAN2|VSS_VDD); // nastaveni A/D prevodniku pro naraznik
0859: BCF 1F.4
085A: BCF 1F.5
085B: MOVF 1B,W
085C: ANDLW 80
085D: IORLW 04
085E: MOVWF 1B
.................... setup_adc(ADC_CLOCK_INTERNAL);
085F: BCF 1F.6
0860: BCF 03.5
0861: BSF 1F.6
0862: BSF 1F.7
0863: BSF 03.5
0864: BCF 1F.7
0865: BCF 03.5
0866: BSF 1F.0
.................... set_adc_channel(2);
0867: MOVLW 10
0868: MOVWF 78
0869: MOVF 1F,W
086A: ANDLW C7
086B: IORWF 78,W
086C: MOVWF 1F
.................... setup_timer_1(T1_INTERNAL|T1_DIV_BY_1); // Casovac pro naraznik
086D: MOVLW 85
086E: MOVWF 10
.................... setup_ccp1(CCP_COMPARE_RESET_TIMER);
086F: BSF 03.5
0870: BSF 06.3
0871: MOVLW 0B
0872: BCF 03.5
0873: MOVWF 17
.................... CCP_1=(2^10)-1; // prevod kazdou 1ms
0874: CLRF 16
0875: MOVLW 07
0876: MOVWF 15
....................
.................... setup_comparator(A0_VR_A1_VR); // inicializace komparatoru pro cidla cary
0877: MOVLW 02
0878: BSF 03.5
0879: MOVWF 1C
087A: MOVF 05,W
087B: IORLW 03
087C: MOVWF 05
087D: MOVLW 03
087E: MOVWF 77
087F: DECFSZ 77,F
0880: GOTO 07F
0881: MOVF 1C,W
0882: BCF 03.5
0883: BCF 0D.6
.................... setup_vref(VREF_HIGH|TRESHOLD); // 32 kroku od 0.25 do 0.75 Vdd
0884: MOVLW 8A
0885: BSF 03.5
0886: MOVWF 1D
....................
.................... Beep(1000,200); //double beep
0887: MOVLW 03
0888: MOVWF 7D
0889: MOVLW E8
088A: MOVWF 7C
088B: CLRF 21
088C: MOVLW C8
088D: MOVWF 20
088E: BCF 0A.3
088F: BCF 03.5
0890: CALL 071
0891: BSF 0A.3
.................... Delay_ms(50);
0892: MOVLW 32
0893: MOVWF 7D
0894: BCF 0A.3
0895: CALL 09D
0896: BSF 0A.3
.................... Beep(1000,200);
0897: MOVLW 03
0898: MOVWF 7D
0899: MOVLW E8
089A: MOVWF 7C
089B: BSF 03.5
089C: CLRF 21
089D: MOVLW C8
089E: MOVWF 20
089F: BCF 0A.3
08A0: BCF 03.5
08A1: CALL 071
08A2: BSF 0A.3
.................... Delay_ms(1000); // 1s
08A3: MOVLW 04
08A4: MOVWF 73
08A5: MOVLW FA
08A6: MOVWF 7D
08A7: BCF 0A.3
08A8: CALL 09D
08A9: BSF 0A.3
08AA: DECFSZ 73,F
08AB: GOTO 0A5
....................
.................... // povoleni rizeni rychlosti zataceni pres preruseni
.................... enable_interrupts(INT_TIMER2);
08AC: BSF 03.5
08AD: BSF 0C.1
.................... enable_interrupts(GLOBAL);
08AE: MOVLW C0
08AF: BCF 03.5
08B0: IORWF 0B,F
....................
.................... /*---------------------------------------------------------------------------*/
.................... sensors=S;
08B1: MOVLW 03
08B2: MOVWF 40
.................... line=S;
08B3: MOVWF 41
.................... last=S;
08B4: MOVWF 44
.................... movement=S;
08B5: MOVWF 45
.................... speed=FW_POMALU;
08B6: MOVLW E6
08B7: MOVWF 42
....................
.................... diagnostika();
08B8: BCF 0A.3
08B9: GOTO 1D1
08BA: BSF 0A.3
.................... cikcak(); // toc se, abys nasel caru
08BB: BCF 0A.3
08BC: CALL 3C4
08BD: BSF 0A.3
.................... Delay_ms(500);
08BE: MOVLW 02
08BF: MOVWF 73
08C0: MOVLW FA
08C1: MOVWF 7D
08C2: BCF 0A.3
08C3: CALL 09D
08C4: BSF 0A.3
08C5: DECFSZ 73,F
08C6: GOTO 0C0
.................... Beep(1000,200);
08C7: MOVLW 03
08C8: MOVWF 7D
08C9: MOVLW E8
08CA: MOVWF 7C
08CB: BSF 03.5
08CC: CLRF 21
08CD: MOVLW C8
08CE: MOVWF 20
08CF: BCF 0A.3
08D0: BCF 03.5
08D1: CALL 071
08D2: BSF 0A.3
.................... Delay_ms(500);
08D3: MOVLW 02
08D4: MOVWF 73
08D5: MOVLW FA
08D6: MOVWF 7D
08D7: BCF 0A.3
08D8: CALL 09D
08D9: BSF 0A.3
08DA: DECFSZ 73,F
08DB: GOTO 0D5
....................
.................... while(true) // hlavni smycka (jizda podle cary)
.................... {
.................... sensors = RSENSOR; // cteni senzoru na caru
08DC: CLRF 40
08DD: BSF 03.5
08DE: BTFSS 1C.7
08DF: GOTO 0E3
08E0: BCF 03.5
08E1: INCF 40,F
08E2: BSF 03.5
.................... sensors |= LSENSOR << 1;
08E3: MOVLW 00
08E4: BTFSC 1C.6
08E5: MOVLW 01
08E6: MOVWF 77
08E7: BCF 03.0
08E8: RLF 77,F
08E9: MOVF 77,W
08EA: BCF 03.5
08EB: IORWF 40,F
....................
.................... if ((read_adc(ADC_READ_ONLY)<BUMPER_TRESHOLD) && (cihla==0)) objizdka();
08EC: BTFSC 1F.2
08ED: GOTO 0EC
08EE: MOVF 1E,W
08EF: SUBLW 7F
08F0: BTFSS 03.0
08F1: GOTO 0F8
08F2: MOVF 47,F
08F3: BTFSS 03.2
08F4: GOTO 0F8
08F5: BCF 0A.3
08F6: GOTO 4B2
08F7: BSF 0A.3
....................
.................... switch (sensors) // zatacej podle toho, kde vidis caru
.................... {
08F8: MOVF 40,W
08F9: XORLW 03
08FA: BTFSC 03.2
08FB: GOTO 103
08FC: XORLW 01
08FD: BTFSC 03.2
08FE: GOTO 117
08FF: XORLW 03
0900: BTFSC 03.2
0901: GOTO 150
0902: GOTO 189
.................... case S: // rovne
.................... FL; FR; // pokud se jede dlouho rovne, tak pridej
0903: BSF 03.5
0904: BCF 06.7
0905: BCF 03.5
0906: BCF 06.7
0907: BSF 03.5
0908: BCF 06.6
0909: BCF 03.5
090A: BSF 06.6
090B: BSF 03.5
090C: BCF 06.5
090D: BCF 03.5
090E: BCF 06.5
090F: BSF 03.5
0910: BCF 06.4
0911: BCF 03.5
0912: BSF 06.4
.................... dira=0;
0913: CLRF 46
.................... movement=S;
0914: MOVLW 03
0915: MOVWF 45
.................... continue;
0916: GOTO 0DC
.................... case L: // trochu vlevo
.................... GO(L, F, FW_POMALU+rovinka); GO(R, F, FW_STREDNE+rovinka);
0917: MOVF 01,W
0918: MOVWF 73
0919: MOVLW E6
091A: ADDWF 43,W
091B: SUBWF 73,W
091C: BTFSC 03.2
091D: GOTO 120
091E: BTFSC 03.0
091F: GOTO 129
0920: BSF 03.5
0921: BCF 06.7
0922: BCF 03.5
0923: BCF 06.7
0924: BSF 03.5
0925: BCF 06.6
0926: BCF 03.5
0927: BSF 06.6
0928: GOTO 131
0929: BSF 03.5
092A: BCF 06.6
092B: BCF 03.5
092C: BCF 06.6
092D: BSF 03.5
092E: BCF 06.7
092F: BCF 03.5
0930: BCF 06.7
0931: MOVF 01,W
0932: MOVWF 73
0933: MOVLW F0
0934: ADDWF 43,W
0935: SUBWF 73,W
0936: BTFSC 03.2
0937: GOTO 13A
0938: BTFSC 03.0
0939: GOTO 143
093A: BSF 03.5
093B: BCF 06.5
093C: BCF 03.5
093D: BCF 06.5
093E: BSF 03.5
093F: BCF 06.4
0940: BCF 03.5
0941: BSF 06.4
0942: GOTO 14B
0943: BSF 03.5
0944: BCF 06.4
0945: BCF 03.5
0946: BCF 06.4
0947: BSF 03.5
0948: BCF 06.5
0949: BCF 03.5
094A: BCF 06.5
.................... line=L;
094B: MOVLW 02
094C: MOVWF 41
.................... dira=0;
094D: CLRF 46
.................... movement=L;
094E: MOVWF 45
.................... continue;
094F: GOTO 0DC
.................... case R: // trochu vpravo
.................... GO(R, F, FW_POMALU+rovinka); GO(L, F, FW_STREDNE+rovinka);
0950: MOVF 01,W
0951: MOVWF 73
0952: MOVLW E6
0953: ADDWF 43,W
0954: SUBWF 73,W
0955: BTFSC 03.2
0956: GOTO 159
0957: BTFSC 03.0
0958: GOTO 162
0959: BSF 03.5
095A: BCF 06.5
095B: BCF 03.5
095C: BCF 06.5
095D: BSF 03.5
095E: BCF 06.4
095F: BCF 03.5
0960: BSF 06.4
0961: GOTO 16A
0962: BSF 03.5
0963: BCF 06.4
0964: BCF 03.5
0965: BCF 06.4
0966: BSF 03.5
0967: BCF 06.5
0968: BCF 03.5
0969: BCF 06.5
096A: MOVF 01,W
096B: MOVWF 73
096C: MOVLW F0
096D: ADDWF 43,W
096E: SUBWF 73,W
096F: BTFSC 03.2
0970: GOTO 173
0971: BTFSC 03.0
0972: GOTO 17C
0973: BSF 03.5
0974: BCF 06.7
0975: BCF 03.5
0976: BCF 06.7
0977: BSF 03.5
0978: BCF 06.6
0979: BCF 03.5
097A: BSF 06.6
097B: GOTO 184
097C: BSF 03.5
097D: BCF 06.6
097E: BCF 03.5
097F: BCF 06.6
0980: BSF 03.5
0981: BCF 06.7
0982: BCF 03.5
0983: BCF 06.7
.................... line=R;
0984: MOVLW 01
0985: MOVWF 41
.................... dira=0;
0986: CLRF 46
.................... movement=R;
0987: MOVWF 45
.................... continue;
0988: GOTO 0DC
.................... default: // kdyz jsou obe cidla mimo caru, tak pokracuj dal
.................... }
.................... rovinka=0;
0989: CLRF 43
.................... if (dira>=T_DIRA) prejeddiru();
098A: MOVF 46,W
098B: SUBLW 54
098C: BTFSC 03.0
098D: GOTO 191
098E: BCF 0A.3
098F: GOTO 5B0
0990: BSF 0A.3
.................... if (last!=line) // pokud si prejel caru z jedne strany na druhou stranu, tak zabrzdi
0991: MOVF 41,W
0992: SUBWF 44,W
0993: BTFSC 03.2
0994: GOTO 199
.................... {
.................... last=line;
0995: MOVF 41,W
0996: MOVWF 44
.................... speed=FW_ZATACKA;
0997: MOVLW C8
0998: MOVWF 42
.................... }
.................... if (L==line) // kdyz jsou obe cidla mimo caru, zatoc na caru
0999: MOVF 41,W
099A: SUBLW 02
099B: BTFSS 03.2
099C: GOTO 1BD
.................... {
.................... STOPL;
099D: BSF 03.5
099E: BCF 06.6
099F: BCF 03.5
09A0: BCF 06.6
09A1: BSF 03.5
09A2: BCF 06.7
09A3: BCF 03.5
09A4: BCF 06.7
.................... GO(R, F, speed);
09A5: MOVF 01,W
09A6: SUBWF 42,W
09A7: BTFSS 03.0
09A8: GOTO 1B2
09A9: BSF 03.5
09AA: BCF 06.5
09AB: BCF 03.5
09AC: BCF 06.5
09AD: BSF 03.5
09AE: BCF 06.4
09AF: BCF 03.5
09B0: BSF 06.4
09B1: GOTO 1BA
09B2: BSF 03.5
09B3: BCF 06.4
09B4: BCF 03.5
09B5: BCF 06.4
09B6: BSF 03.5
09B7: BCF 06.5
09B8: BCF 03.5
09B9: BCF 06.5
.................... movement=L;
09BA: MOVLW 02
09BB: MOVWF 45
.................... }
.................... else
09BC: GOTO 1DC
.................... {
.................... STOPR;
09BD: BSF 03.5
09BE: BCF 06.4
09BF: BCF 03.5
09C0: BCF 06.4
09C1: BSF 03.5
09C2: BCF 06.5
09C3: BCF 03.5
09C4: BCF 06.5
.................... GO(L, F, speed);
09C5: MOVF 01,W
09C6: SUBWF 42,W
09C7: BTFSS 03.0
09C8: GOTO 1D2
09C9: BSF 03.5
09CA: BCF 06.7
09CB: BCF 03.5
09CC: BCF 06.7
09CD: BSF 03.5
09CE: BCF 06.6
09CF: BCF 03.5
09D0: BSF 06.6
09D1: GOTO 1DA
09D2: BSF 03.5
09D3: BCF 06.6
09D4: BCF 03.5
09D5: BCF 06.6
09D6: BSF 03.5
09D7: BCF 06.7
09D8: BCF 03.5
09D9: BCF 06.7
.................... movement=R;
09DA: MOVLW 01
09DB: MOVWF 45
.................... }
.................... } // while(true)
09DC: GOTO 0DC
.................... }
....................
....................
09DD: SLEEP
 
Configuration Fuses:
Word 1: 3F38 NOWDT NOPUT MCLR NOBROWNOUT NOLVP NOCPD NOWRT NODEBUG CCPB0 NOPROTECT INTRC_IO
Word 2: 3FFC NOFCMEN NOIESO
/roboti/istrobot/merkur/dokumentace/obrazky/PIC16F88/tank.PJT
0,0 → 1,40
[PROJECT]
Target=tank.HEX
Development_Mode=
Processor=0x688F
ToolSuite=CCS
 
[Directories]
Include=C:\Program Files\PICC\devices\;C:\Program Files\PICC\drivers\;C:\library\CCS;
Library=
LinkerScript=
 
[Target Data]
FileList=tank.c;
BuildTool=C-COMPILER
OptionString=+FM
AdditionalOptionString=
BuildRequired=1
 
[tank.c]
Type=4
Path=
FileList=
BuildTool=
OptionString=
AdditionalOptionString=
 
[mru-list]
1=tank.c
 
[Windows]
0=0000 tank.c 0 0 796 451 3 0
 
[Opened Files]
1=D:\KAKLIK\programy\PIC_C\roboti\merkur\PIC16F88\tank.c
2=C:\Program Files\PICC\devices\16F88.h
3=
4=C:\Program Files\PICC\devices\16F88.h
5=
6=
7=
/roboti/istrobot/merkur/dokumentace/obrazky/PIC16F88/tank.SYM
0,0 → 1,114
003 STATUS
015 CCP_1_LOW
015-016 CCP_1
016 CCP_1_HIGH
020 @INTERRUPT_AREA
021 @INTERRUPT_AREA
022 @INTERRUPT_AREA
023 @INTERRUPT_AREA
024 @INTERRUPT_AREA
025 @INTERRUPT_AREA
026 @INTERRUPT_AREA
027 @INTERRUPT_AREA
028 @INTERRUPT_AREA
029-038 SendData
039.0 bit
03A fcslo
03B fcshi
03C stuff
03D flag_flag
03E fcs_flag
03F i
040 sensors
041 line
042 speed
043 rovinka
044 last
045 movement
046 dira
047 cihla
048-06F AXstring
070 @sprintf_string
071-072 main.n
073-074 prejeddiru.n
073-074 diagnostika.n
073-074 objizdka.n
073 main.@SCRATCH
075-076 cikcak.n
075 ls
075 objizdka.@SCRATCH
075 prejeddiru.@SCRATCH
076 rs
077 @SCRATCH
078 @SCRATCH
078 _RETURN_
079 @SCRATCH
07A @SCRATCH
07B @SCRATCH
07C-07D beep.period
07C SendPacket.data
07C diagnostika.@SCRATCH
07C cikcak.@SCRATCH
07D @delay_ms1.P1
07D @PRINTF_U_331.P2
07D SendPacket.@SCRATCH
07E @PRINTF_U_331.P1
07E SendByte.inbyte
09C.6 C1OUT
09C.7 C2OUT
0A0 @DIV88.P1
0A0 SendByte.k
0A0 @SPRINTF.P1
0A0-0A1 beep.length
0A1 SendByte.bt
0A1 @DIV88.P1
0A2 fcsbit.tbyte
0A2-0A3 beep.nn
0A2 SendByte.@SCRATCH
0A2 @DIV88.@SCRATCH
0A3 fcsbit.@SCRATCH
0A4 @delay_us1.P1
0A4 fcsbit.@SCRATCH
 
009D @delay_ms1
005C @delay_us1
012E flipout
0193 fcsbit
0135 SendBit
0173 SendByte
0379 SendPacket
0049 TIMER2_isr
0071 beep
01D1 diagnostika
0037 @const10190
00B2 @SPRINTF
00BC @DIV88
00D3 @PRINTF_U_331
03C4 cikcak
04B2 objizdka
05B0 prejeddiru
0800 main
0800 @cinit
0666 sem
 
Project Files:
D:\KAKLIK\programy\PIC_C\roboti\merkur\PIC16F88\tank.c
D:\KAKLIK\programy\PIC_C\roboti\merkur\PIC16F88\tank.h
C:\Program Files\PICC\devices\16F88.h
D:\KAKLIK\programy\PIC_C\roboti\merkur\PIC16F88\AX25.c
 
Compiler Settings:
Processor: PIC16F88
Pointer Size: 8
ADC Range: 0-255
Opt Level: 9
Short,Int,Long: 1,8,16
 
Output Files:
Errors: D:\KAKLIK\programy\PIC_C\roboti\merkur\PIC16F88\tank.err
INHX8: D:\KAKLIK\programy\PIC_C\roboti\merkur\PIC16F88\tank.HEX
Symbols: D:\KAKLIK\programy\PIC_C\roboti\merkur\PIC16F88\tank.SYM
List: D:\KAKLIK\programy\PIC_C\roboti\merkur\PIC16F88\tank.LST
Debug/COFF: D:\KAKLIK\programy\PIC_C\roboti\merkur\PIC16F88\tank.cof
Call Tree: D:\KAKLIK\programy\PIC_C\roboti\merkur\PIC16F88\tank.tre
Statistics: D:\KAKLIK\programy\PIC_C\roboti\merkur\PIC16F88\tank.sta
/roboti/istrobot/merkur/dokumentace/obrazky/PIC16F88/tank.cof
Cannot display: file marked as a binary type.
svn:mime-type = application/octet-stream
Property changes:
Added: svn:mime-type
+application/octet-stream
\ No newline at end of property
/roboti/istrobot/merkur/dokumentace/obrazky/PIC16F88/tank.err
0,0 → 1,0
No Errors
/roboti/istrobot/merkur/dokumentace/obrazky/PIC16F88/tank.h
0,0 → 1,5
#include <16F88.h>
#device adc=8
#fuses NOWDT,INTRC_IO, NOPUT, MCLR, NOBROWNOUT, NOLVP, NOCPD, NOWRT, NODEBUG, NOPROTECT, NOFCMEN, NOIESO
#use delay(clock=4000000)
 
/roboti/istrobot/merkur/dokumentace/obrazky/PIC16F88/tank.sta
0,0 → 1,45
 
ROM used: 2140 (52%)
2526 (62%) including unused fragments
 
3 Average locations per line
5 Average locations per statement
 
RAM used: 89 (51%) at main() level
101 (58%) worst case
 
Lines Stmts % Files
----- ----- --- -----
351 390 85 D:\KAKLIK\programy\PIC_C\roboti\merkur\PIC16F88\tank.c
6 0 0 D:\KAKLIK\programy\PIC_C\roboti\merkur\PIC16F88\tank.h
275 0 0 C:\Program Files\PICC\devices\16F88.h
136 67 8 D:\KAKLIK\programy\PIC_C\roboti\merkur\PIC16F88\AX25.c
----- -----
1536 914 Total
 
Page ROM % RAM Functions:
---- --- --- --- ----------
0 21 1 1 @delay_ms1
0 21 1 1 @delay_us1
0 7 0 0 flipout
0 62 3 0 SendBit
0 94 4 4 SendByte
0 19 1 0 TIMER2_isr
0 44 2 6 beep
0 499 23 3 diagnostika
0 18 1 0 @const10190
0 10 0 1 @SPRINTF
0 23 1 3 @DIV88
0 91 4 2 @PRINTF_U_331
0 238 11 3 cikcak
0 254 12 3 objizdka
0 206 10 3 prejeddiru
1 478 22 3 main
 
Segment Used Free
--------- ---- ----
00000-00003 4 0
00004-00036 51 0
00037-007FF 1607 386
00800-00FFF 478 1570
 
/roboti/istrobot/merkur/dokumentace/obrazky/PIC16F88/tank.tre
0,0 → 1,136
ÀÄtank
ÃÄmain 1/478 Ram=3
³ ÃÄ??0??
³ ÃÄbeep 0/44 Ram=6
³ ³ ÃÄ@delay_us1 0/21 Ram=1
³ ³ ÀÄ@delay_us1 0/21 Ram=1
³ ÃÄ@delay_ms1 0/21 Ram=1
³ ÃÄbeep 0/44 Ram=6
³ ³ ÃÄ@delay_us1 0/21 Ram=1
³ ³ ÀÄ@delay_us1 0/21 Ram=1
³ ÃÄ@delay_ms1 0/21 Ram=1
³ ÃÄdiagnostika 0/499 Ram=3
³ ³ ÃÄbeep 0/44 Ram=6
³ ³ ³ ÃÄ@delay_us1 0/21 Ram=1
³ ³ ³ ÀÄ@delay_us1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄbeep 0/44 Ram=6
³ ³ ³ ÃÄ@delay_us1 0/21 Ram=1
³ ³ ³ ÀÄ@delay_us1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄbeep 0/44 Ram=6
³ ³ ³ ÃÄ@delay_us1 0/21 Ram=1
³ ³ ³ ÀÄ@delay_us1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄbeep 0/44 Ram=6
³ ³ ³ ÃÄ@delay_us1 0/21 Ram=1
³ ³ ³ ÀÄ@delay_us1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@SPRINTF 0/10 Ram=1
³ ³ ÃÄ@SPRINTF 0/10 Ram=1
³ ³ ÃÄ@SPRINTF 0/10 Ram=1
³ ³ ÃÄ@PRINTF_U_331 0/91 Ram=2
³ ³ ³ ÃÄ@DIV88 0/23 Ram=3
³ ³ ³ ÃÄ@SPRINTF 0/10 Ram=1
³ ³ ³ ÃÄ@SPRINTF 0/10 Ram=1
³ ³ ³ ÃÄ@SPRINTF 0/10 Ram=1
³ ³ ³ ÃÄ@DIV88 0/23 Ram=3
³ ³ ³ ÃÄ@SPRINTF 0/10 Ram=1
³ ³ ³ ÀÄ@SPRINTF 0/10 Ram=1
³ ³ ÃÄ@const10190 0/18 Ram=0
³ ³ ÃÄ@SPRINTF 0/10 Ram=1
³ ³ ÃÄ@PRINTF_U_331 0/91 Ram=2
³ ³ ³ ÃÄ@DIV88 0/23 Ram=3
³ ³ ³ ÃÄ@SPRINTF 0/10 Ram=1
³ ³ ³ ÃÄ@SPRINTF 0/10 Ram=1
³ ³ ³ ÃÄ@SPRINTF 0/10 Ram=1
³ ³ ³ ÃÄ@DIV88 0/23 Ram=3
³ ³ ³ ÃÄ@SPRINTF 0/10 Ram=1
³ ³ ³ ÀÄ@SPRINTF 0/10 Ram=1
³ ³ ÃÄSendPacket (Inline) Ram=2
³ ³ ³ ÃÄSendByte 0/94 Ram=4
³ ³ ³ ³ ÃÄfcsbit (Inline) Ram=3
³ ³ ³ ³ ÃÄflipout 0/7 Ram=0
³ ³ ³ ³ ÃÄSendBit 0/62 Ram=0
³ ³ ³ ³ ÃÄflipout 0/7 Ram=0
³ ³ ³ ³ ÀÄSendBit 0/62 Ram=0
³ ³ ³ ÃÄSendByte 0/94 Ram=4
³ ³ ³ ³ ÃÄfcsbit (Inline) Ram=3
³ ³ ³ ³ ÃÄflipout 0/7 Ram=0
³ ³ ³ ³ ÃÄSendBit 0/62 Ram=0
³ ³ ³ ³ ÃÄflipout 0/7 Ram=0
³ ³ ³ ³ ÀÄSendBit 0/62 Ram=0
³ ³ ³ ÃÄSendByte 0/94 Ram=4
³ ³ ³ ³ ÃÄfcsbit (Inline) Ram=3
³ ³ ³ ³ ÃÄflipout 0/7 Ram=0
³ ³ ³ ³ ÃÄSendBit 0/62 Ram=0
³ ³ ³ ³ ÃÄflipout 0/7 Ram=0
³ ³ ³ ³ ÀÄSendBit 0/62 Ram=0
³ ³ ³ ÃÄSendByte 0/94 Ram=4
³ ³ ³ ³ ÃÄfcsbit (Inline) Ram=3
³ ³ ³ ³ ÃÄflipout 0/7 Ram=0
³ ³ ³ ³ ÃÄSendBit 0/62 Ram=0
³ ³ ³ ³ ÃÄflipout 0/7 Ram=0
³ ³ ³ ³ ÀÄSendBit 0/62 Ram=0
³ ³ ³ ÃÄSendByte 0/94 Ram=4
³ ³ ³ ³ ÃÄfcsbit (Inline) Ram=3
³ ³ ³ ³ ÃÄflipout 0/7 Ram=0
³ ³ ³ ³ ÃÄSendBit 0/62 Ram=0
³ ³ ³ ³ ÃÄflipout 0/7 Ram=0
³ ³ ³ ³ ÀÄSendBit 0/62 Ram=0
³ ³ ³ ÀÄSendByte 0/94 Ram=4
³ ³ ³ ÃÄfcsbit (Inline) Ram=3
³ ³ ³ ÃÄflipout 0/7 Ram=0
³ ³ ³ ÃÄSendBit 0/62 Ram=0
³ ³ ³ ÃÄflipout 0/7 Ram=0
³ ³ ³ ÀÄSendBit 0/62 Ram=0
³ ³ ÀÄ@delay_ms1 0/21 Ram=1
³ ÃÄcikcak 0/238 Ram=3
³ ³ ÀÄ@delay_ms1 0/21 Ram=1
³ ÃÄ@delay_ms1 0/21 Ram=1
³ ÃÄbeep 0/44 Ram=6
³ ³ ÃÄ@delay_us1 0/21 Ram=1
³ ³ ÀÄ@delay_us1 0/21 Ram=1
³ ÃÄ@delay_ms1 0/21 Ram=1
³ ÃÄobjizdka 0/254 Ram=3
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄbeep 0/44 Ram=6
³ ³ ³ ÃÄ@delay_us1 0/21 Ram=1
³ ³ ³ ÀÄ@delay_us1 0/21 Ram=1
³ ³ ÃÄcikcak 0/238 Ram=3
³ ³ ³ ÀÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÃÄ@delay_ms1 0/21 Ram=1
³ ³ ÀÄcikcak 0/238 Ram=3
³ ³ ÀÄ@delay_ms1 0/21 Ram=1
³ ÀÄprejeddiru 0/206 Ram=3
³ ÃÄbeep 0/44 Ram=6
³ ³ ÃÄ@delay_us1 0/21 Ram=1
³ ³ ÀÄ@delay_us1 0/21 Ram=1
³ ÃÄ@delay_ms1 0/21 Ram=1
³ ÃÄ@delay_ms1 0/21 Ram=1
³ ÃÄbeep 0/44 Ram=6
³ ³ ÃÄ@delay_us1 0/21 Ram=1
³ ³ ÀÄ@delay_us1 0/21 Ram=1
³ ÃÄ@delay_ms1 0/21 Ram=1
³ ÀÄcikcak 0/238 Ram=3
³ ÀÄ@delay_ms1 0/21 Ram=1
ÀÄTIMER2_isr 0/19 Ram=0
/roboti/istrobot/merkur/dokumentace/obrazky/PIC16F88/verze/1 tank.c
0,0 → 1,313
#include "tank.h"
 
#define TXo PIN_B1 // To the transmitter modulator
#include "AX25.c" // podprogram pro prenos telemetrie
 
//motory //Napred vypnout potom zapnout!
#define FR output_low(PIN_B5); output_high(PIN_B4) // Vpred
#define FL output_low(PIN_B7); output_high(PIN_B6)
#define BR output_low(PIN_B4); output_high(PIN_B5) // Vzad
#define BL output_low(PIN_B6); output_high(PIN_B7)
#define STOPR output_low(PIN_B4);output_low(PIN_B5)
#define STOPL output_low(PIN_B6);output_low(PIN_B7)
 
#define L 0b10 // left
#define R 0b01 // right
#define S 0b11 // straight
 
#define COUVANI 1600 // couvnuti po zjisteni diry
#define MEZERA 5400 // za jak dlouho bude ztracena cara
#define PRES_DIRU 1000 // velikost mezery v care
#define BRZDENI 5000 // doba ptrebna k zastaveni jednoho motoru
 
//cidla
#define RSENSOR C2OUT // Senzory na caru
#define LSENSOR C1OUT
#define BUMPER PIN_A4 // sensor na cihlu
 
#define DIAG_SERVO PIN_B2 // Propojka pro diagnosticky mod
#define DIAG_SENSORS PIN_B3 // Propojka pro diagnosticky mod
 
#DEFINE SOUND_HI PIN_A7
#DEFINE SOUND_LO PIN_A6
 
char AXstring[40]; // Buffer pro prenos telemetrie
 
#define GO(motor, direction, power) if(get_timer0()<=power) \
{direction##motor;} \
else \
{stop##motor;}
 
int movement; // smer minuleho pohybu
int line; // na ktere strane byla detekovana cara
unsigned int16 dira; // pocitadlo pro nalezeni preruseni cary
int speed,speedL,speedR;
 
// Primitivni Pipani
void beep(unsigned int16 period, unsigned int16 length)
{
unsigned int16 nn;
 
for(nn=length; nn>0; nn--)
{
output_high(SOUND_HI);output_low(SOUND_LO);
delay_us(period);
output_high(SOUND_LO);output_low(SOUND_HI);
delay_us(period);
}
}
#int_TIMER2
void TIMER2_isr()
{
switch(line) // upravime smer
{
case S: //obe cidla na care
if(speedL<200)speedL++;
if(speedR<200)speedR++;
break; // vrat se zpet na cteni cidel
case L: // cara je pod levym cidlem, trochu zatocime
if (speedL>100)speedL -- ;
if (speedR<200)speedR ++ ;
break;
case R: // cara pod pravym cidlem
if (speedR>100)speedR -- ;
if (speedL<200)speedL ++ ;
break;
default:
}
}
// Diagnostika pohonu, hejbne vsema motorama ve vsech smerech
void diagnostika()
{
unsigned int16 n;
 
while (input(DIAG_SERVO)) // Propojka, ktera spousti diagnostiku
{
for (n=500; n<800; n+=100)
{
beep(n,n); //beep UP
};
Delay_ms(1000);
//zastav vse
STOPL; STOPR;
//pravy pas
FR; Delay_ms(1000); STOPR; Delay_ms(1000);
BR; Delay_ms(1000); STOPR; Delay_ms(1000);
Beep(880,100); Delay_ms(1000);
//levy pas
FL; Delay_ms(1000); STOPL; Delay_ms(1000);
BL; Delay_ms(1000); STOPL; Delay_ms(1000);
Beep(880,100); Delay_ms(1000);
//oba pasy
FL; FR; Delay_ms(1000); STOPL; STOPR; Delay_ms(1000);
BL; BR; Delay_ms(1000); STOPL; STOPR; Delay_ms(1000);
};
 
while (input(DIAG_SENSORS))
{
int ls, rs;
while(!input(BUMPER)){beep(1100,100); Delay_ms(50);}
set_adc_channel(RSENSOR);
Delay_us(20);
rs=read_adc();
set_adc_channel(LSENSOR);
Delay_us(20);
ls=read_adc();
sprintf(AXstring,"L: %U R: %U\0", ls, rs); // Convert DATA to String.
SendPacket(&AXstring[0]);
delay_ms(1000);
};
}
 
void cikcak()
{
int n;
switch(movement) // podivej se na jednu stranu
{
case L:
FL;BR;
movement=R;
break;
case R:
FR;BL;
movement=L;
break;
case S:
FR;BL;
movement=L;
break;
}
while (0==(RSENSOR|LSENSOR))
{
if (n==50) // asi bude na druhe strane
{
STOPR;STOPL;
n=0;
switch(movement)
{
case L:
FL;BR;
movement=R;
break;
case R:
FR;BL;
movement=L;
break;
}
}
Delay_ms(5);
n++;
}
STOPL;STOPR; // nasli jsme caru
line=S;
}
void objizdka()
{
BL;BR;Delay_ms(300);
STOPR;STOPL;
beep(1000,1000);
Delay_ms(500);
beep(1000,1000);
Delay_ms(1000);
 
 
 
}
 
void pozordira()
{
beep(800,500);
Delay_ms(50);
beep(800,500);
switch (movement) //vrat se zpet na caru
{
case L:
STOPL;STOPR;
BR;Delay_ms(COUVANI);STOPR;
break;
case R:
STOPL;STOPR;
BL;Delay_ms(COUVANI);STOPL;
break;
case S:
BL; BR; Delay_ms(COUVANI);
STOPL; STOPR;
break;
}
 
FR;FL; Delay_ms(PRES_DIRU); // popojedem dopredu mozna tam bude cara
STOPL; STOPR; movement=S;
cikcak(); // najdi caru
dira=0;
}
 
void main()
{
unsigned int16 rovinka;
int last;
 
STOPL; STOPR;
 
setup_oscillator(OSC_4MHZ|OSC_INTRC); // 4 MHz interni RC oscilator
port_b_pullups(true);
setup_adc_ports(NO_ANALOGS|VSS_VDD);
setup_adc(ADC_OFF);
setup_spi(FALSE);
setup_timer_0(RTCC_INTERNAL|RTCC_DIV_1); // Casovac pro PWM
setup_timer_1(T1_DISABLED); // Casovac pro regulaci
setup_timer_2(T2_DIV_BY_16,50,16);
setup_ccp1(CCP_OFF);
setup_comparator(A0_VR_A1_VR);
setup_vref(VREF_HIGH|15);
enable_interrupts(INT_TIMER2);
enable_interrupts(GLOBAL);
 
diagnostika();
 
Beep(1000,200); //double beep
Delay_ms(50);
Beep(1000,200);
Delay_ms(1000); // 1s
 
// FL; FR;
movement=S;
line=S;
dira=0;
last=0;
rovinka=0;
 
speed=speedL=speedR=200;
 
while(true)
{
line = RSENSOR; // precteni cidel
line |= LSENSOR << 1; // sestav informaci o care
if(line!=0)
{
GO(L, F, speedL); GO(R,F, speedR);
}
else{STOPR; STOPL;}
//sem:
/* switch(line) // upravime smer
{
case S: //obe cidla na care
// if (speedL<speedR) speedL=speedR;
// else speedR=speedL;
GO(L,F,speedL); GO(R,F,speedR) // jedeme rovne
// if(rovinka<BRZDENI) rovinka++; //cara je rovne
// dira=0; // videli jsme caru, proto neni dira
continue; // vrat se zpet na cteni cidel
case L: // cara je pod levym cidlem, trochu zatocime
GO(L, F, speedL); GO(R,F, speedR);
// if(rovinka<BRZDENI) rovinka++; //cara je celkem rovne
// dira=0;
continue;
case R: // cara pod pravym cidlem
GO(R, F, speedR); GO(L, F, speedL);
// if(rovinka<BRZDENI) rovinka++;
// dira=0;
continue;
default: // cara neni pod zadnym cidlem
}*/
 
 
/*switch (last) // zatacka
{
case L: // do leva
BL;STOPR; //zabrzdeni leveho motoru
for(;rovinka>0;rovinka--) //chvili pockej
{
line = RSENSOR; // precteni cidel
line |= LSENSOR << 1; // sestav informaci o care
if(line!=0) goto sem; //kdyz najdes caru, zastav
}
STOPL; FR; // pokracuj v zataceni
while(line==0)
{
line = RSENSOR; // precteni cidel
line |= LSENSOR << 1; // sestav informaci o care
}
movement=L;
rovinka=0; //zataceli jsme, uz neni rovna cara
break;
case R:
BR; STOPL; // zabrzdeni praveho motoru
for(;rovinka>0;rovinka--)
{
line = RSENSOR; // precteni cidel
line |= LSENSOR << 1; // sestav informaci o care
if(line!=0) goto sem;
}
STOPR; FL;
while(line==0)
{
line = RSENSOR; // precteni cidel
line |= LSENSOR << 1; // sestav informaci o care
}
movement=R;
rovinka=0; //zataceli jsme, uz neni rovna cara
break;
}*/
} // while(true)
}
/roboti/istrobot/merkur/dokumentace/obrazky/PIC16F88/verze/2 tank.c
0,0 → 1,331
#include "tank.h"
 
#define DEBUG
 
#define TXo PIN_A3 // To the transmitter modulator
#include "AX25.c" // podprogram pro prenos telemetrie
 
unsigned int8 sensors; // pomocna promenna pro cteni cidel na caru
unsigned int8 line; // na ktere strane byla detekovana cara
unsigned int8 speed; // rychlost zataceni
unsigned int8 rovinka; // pocitadlo pro zjisteni rovneho useku
unsigned int8 last; // kde byla cara, kdyz byly minule cidla mimo
unsigned int8 movement; // obsahuje aktualni smer zataceni
unsigned int8 dira; // pocita dobu po kterou je ztracena cara
 
// Konstanty pro dynamiku pohybu
#define T_DIRA 100 // po jakem case zataceni se detekuje dira
#define INC_SPEED 1 // prirustek rychlosti v jednom kroku
#define FW_POMALU 100 // trochu mimo caru vnitrni pas
#define FW_ZATACKA 200 // rychlost vnejsiho kola pri zataceni
#define FW_STREDNE 110 // trochu mimo caru vnejsi pas
#define COUVANI 600 // couvnuti zpet na caru, po detekci diry
#define PRES_DIRU 300
#define MAX_ROVINKA (255-FW_STREDNE)
#define TRESHOLD 6 // rozhodovaci uroven komparatoru, 0xF = 0.75*Vdd
 
//motory //Napred vypnout potom zapnout!
#define FR output_low(PIN_B5); output_high(PIN_B4) // Vpred
#define FL output_low(PIN_B7); output_high(PIN_B6)
#define BR output_low(PIN_B4); output_high(PIN_B5) // Vzad
#define BL output_low(PIN_B6); output_high(PIN_B7)
#define STOPR output_low(PIN_B4);output_low(PIN_B5) // Zastav
#define STOPL output_low(PIN_B6);output_low(PIN_B7)
 
#define L 0b10 // left
#define R 0b01 // right
#define S 0b11 // straight
 
//cidla
#define RSENSOR C2OUT // Senzory na caru
#define LSENSOR C1OUT
#define BUMPER PIN_A4 // Senzor na cihlu
 
#define DIAG_SERVO PIN_B3 // Propojka pro diagnosticky mod
#define DIAG_SENSORS PIN_B2 // Propojka pro diagnosticky mod
 
#DEFINE SOUND_HI PIN_A6 // komplementarni vystupy pro piezo pipak
#DEFINE SOUND_LO PIN_A7
 
char AXstring[40]; // Buffer pro prenos telemetrie
 
// makro pro PWM
#define GO(motor, direction, power) if(get_timer0()<=power) \
{direction##motor;} \
else \
{stop##motor;}
 
#int_TIMER2
void TIMER2_isr()
{
if (speed<255) speed+=INC_SPEED;
if (rovinka<MAX_ROVINKA) rovinka++;
if (dira<T_DIRA) dira++;
}
 
// Primitivni Pipani
void beep(unsigned int16 period, unsigned int16 length)
{
unsigned int16 nn;
 
for(nn=length; nn>0; nn--)
{
output_high(SOUND_HI);output_low(SOUND_LO);
delay_us(period);
output_high(SOUND_LO);output_low(SOUND_HI);
delay_us(period);
}
}
/******************************************************************************/
void diagnostika()
{
unsigned int16 n;
 
while (input(DIAG_SERVO)) // Propojka, ktera spousti diagnostiku
{
for (n=500; n<800; n+=100)
{
beep(n,n); //beep UP
};
Delay_ms(1000);
//zastav vse
STOPL; STOPR;
//pravy pas
FR; Delay_ms(1000); STOPR; Delay_ms(1000);
BR; Delay_ms(1000); STOPR; Delay_ms(1000);
Beep(880,100); Delay_ms(1000);
//levy pas
FL; Delay_ms(1000); STOPL; Delay_ms(1000);
BL; Delay_ms(1000); STOPL; Delay_ms(1000);
Beep(880,100); Delay_ms(1000);
//oba pasy
FL; FR; Delay_ms(1000); STOPL; STOPR; Delay_ms(1000);
BL; BR; Delay_ms(1000); STOPL; STOPR; Delay_ms(1000);
};
 
while (input(DIAG_SENSORS))
{
int ls, rs;
while(!input(BUMPER)){beep(1100,100); Delay_ms(50);}
set_adc_channel(RSENSOR);
Delay_us(20);
rs=read_adc();
set_adc_channel(LSENSOR);
Delay_us(20);
ls=read_adc();
sprintf(AXstring,"L: %U R: %U\0", ls, rs); // Convert DATA to String.
SendPacket(&AXstring[0]);
delay_ms(1000);
};
}
///////////////////////////////////////////////////////////////////////////////
void cikcak()
{
int n;
switch(movement) // podivej se na jednu stranu
{
case L:
FL;BR;
movement=R;
break;
case R:
FR;BL;
movement=L;
break;
case S:
FR;BL;
movement=L;
break;
}
while (0==(RSENSOR|LSENSOR))
{
if (n==50) //cara asi bude na druhe strane
{
STOPR;STOPL;
n=0;
switch(movement)
{
case L:
FL;BR;
movement=R;
break;
case R:
FR;BL;
movement=L;
break;
}
}
Delay_ms(5);
n++;
}
STOPL;STOPR; // nasli jsme caru
line=S;
}
///////////////////////////////////////////////////////////////////////////////
void objizdka()
{
BL;BR;Delay_ms(300);
STOPR;STOPL;
beep(1000,1000);
Delay_ms(500);
beep(1000,1000);
Delay_ms(1000);
 
 
 
}
///////////////////////////////////////////////////////////////////////////////
void prejeddiru()
{
STOPL;STOPR;
beep(800,500);
Delay_ms(50);
beep(800,500);
switch (movement) //vrat se zpet na caru
{
case L:
BR;Delay_ms(COUVANI);STOPR;
STOPL;STOPR;
break;
case R:
 
BL;Delay_ms(COUVANI);STOPL;
STOPL;STOPR;
break;
case S:
BL; BR; Delay_ms(COUVANI);
STOPL; STOPR;
break;
}
 
FR;FL; Delay_ms(PRES_DIRU); // popojedem dopredu mozna tam bude cara
STOPL; STOPR;
cikcak(); // najdi caru
dira=0;
}
///////////////////////////////////////////////////////////////////////////////
void main()
{
unsigned int16 n; // pro FOR
 
STOPL; STOPR; // prepne vystupy na ovladani motoru na output a zastavi
 
setup_oscillator(OSC_4MHZ|OSC_INTRC); // 4 MHz interni RC oscilator
 
port_b_pullups(TRUE); // pullups pro piano na diagnostiku
setup_spi(FALSE);
setup_timer_0(RTCC_INTERNAL|RTCC_DIV_1); // Casovac pro PWM
 
setup_timer_2(T2_DIV_BY_16,255,10); // Casovac pro regulaci
// preruseni kazdych 10ms
setup_adc_ports(sAN2|VSS_VDD); // nastaveni A/D prevodniku pro naraznik
setup_adc(ADC_CLOCK_INTERNAL);
set_adc_channel(2);
setup_timer_1(T1_INTERNAL|T1_DIV_BY_1); // Casovac pro naraznik
setup_ccp1(CCP_COMPARE_RESET_TIMER);
CCP_1=(2^10)-1; // prevod kazdou 1ms
 
setup_comparator(A0_VR_A1_VR); // inicializace komparatoru pro cidla cary
setup_vref(VREF_HIGH|TRESHOLD); // 32 kroku od 0.25 do 0.75 Vdd
 
Beep(1000,200); //double beep
Delay_ms(50);
Beep(1000,200);
Delay_ms(1000); // 1s
 
// povoleni rizeni rychlosti zataceni pres preruseni
enable_interrupts(INT_TIMER2);
enable_interrupts(GLOBAL);
 
/*---------------------------------------------------------------------------*/
sensors=S;
line=S;
last=S;
movement=S;
speed=FW_POMALU;
 
diagnostika();
cikcak(); // toc se, abys nasel caru
Delay_ms(500);
Beep(1000,200);
Delay_ms(500);
 
while(true) // hlavni smycka (jizda podle cary)
{
 
sensors = RSENSOR; // cteni senzoru na caru
sensors |= LSENSOR << 1;
 
switch (sensors) // zatacej podle toho, kde vidis caru
{
case S: // rovne
GO(L, F, speed); GO(R, F, speed);
// FL; FR; // pokud se jede dlouho rovne, tak pridej
dira=0;
continue;
 
case L: // trochu vlevo
GO(L, F, FW_POMALU+rovinka); GO(R, F, FW_STREDNE+rovinka);
line=L;
dira=0;
continue;
 
case R: // trochu vpravo
GO(R, F, FW_POMALU+rovinka); GO(L, F, FW_STREDNE+rovinka);
line=R;
dira=0;
continue;
 
default: // kdyz jsou obe cidla mimo caru, tak pokracuj dal
}
rovinka=0;
// if (dira>=T_DIRA) prejeddiru();
if (last!=line) // pokud si prejel caru z jedne strany na druhou stranu, tak zabrzdi
{
last=line;
speed=FW_ZATACKA;
}
else speed=255;
/* if (dira==0)
{
if (L==line) // kdyz jsou obe cidla mimo caru, zabrzdi vnitrni kolo
{
BL;
for(n=4000;n>0;n--) // Delay
{
line = RSENSOR; // precteni cidel
line |= LSENSOR << 1; // sestav informaci o care
if(line!=0) break;
}
STOPL;
}
else
{
BR;
for(n=4000;n>0;n--) // Delay
{
line = RSENSOR; // precteni cidel
line |= LSENSOR << 1; // sestav informaci o care
if(line!=0) break;
}
STOPR;
}
}*/
if (L==line) // kdyz jsou obe cidla mimo caru, zatoc na caru
{
STOPL;
GO(R, F, speed);
movement=L;
}
else
{
STOPR;
GO(L, F, speed);
movement=R;
}
} // while(true)
}
 
/roboti/istrobot/merkur/dokumentace/obrazky/PIC16F88/verze/3 tank.c
0,0 → 1,350
#include "tank.h"
 
#define DEBUG
 
#define TXo PIN_A3 // To the transmitter modulator
#include "AX25.c" // podprogram pro prenos telemetrie
 
unsigned int8 sensors; // pomocna promenna pro cteni cidel na caru
unsigned int8 line; // na ktere strane byla detekovana cara
unsigned int8 speed; // rychlost zataceni
unsigned int8 rovinka; // pocitadlo pro zjisteni rovneho useku
unsigned int8 last; // kde byla cara, kdyz byly minule cidla mimo
unsigned int8 movement; // obsahuje aktualni smer zataceni
unsigned int8 dira; // pocita dobu po kterou je ztracena cara
unsigned int8 cihla; // urcuje za jak dlouho muze byt znova detekovana cihla
 
// Konstanty pro dynamiku pohybu
#define T_DIRA 85 // po jakem case zataceni se detekuje dira
#define INC_SPEED 1 // prirustek rychlosti v jednom kroku
#define FW_POMALU 230 // trochu mimo caru vnitrni pas
#define FW_ZATACKA 200 // rychlost vnejsiho kola pri zataceni
#define FW_STREDNE 240 // trochu mimo caru vnejsi pas
#define COUVANI 600 // couvnuti zpet na caru, po detekci diry
#define PRES_DIRU 150
#define MAX_ROVINKA (255-FW_STREDNE)
#define TRESHOLD 10 // rozhodovaci uroven komparatoru, 0xF = 0.75*Vdd
#define BUMPER_TRESHOLD 128
#define CIK_CAK 20000
#define T_CIHLA 100 // perioda detekce cihly
 
//motory //Napred vypnout potom zapnout!
#define FR output_low(PIN_B5); output_high(PIN_B4) // Vpred
#define FL output_low(PIN_B7); output_high(PIN_B6)
#define BR output_low(PIN_B4); output_high(PIN_B5) // Vzad
#define BL output_low(PIN_B6); output_high(PIN_B7)
#define STOPR output_low(PIN_B4);output_low(PIN_B5) // Zastav
#define STOPL output_low(PIN_B6);output_low(PIN_B7)
 
#define L 0b10 // left
#define R 0b01 // right
#define S 0b11 // straight
 
//cidla
#define RSENSOR C2OUT // Senzory na caru
#define LSENSOR C1OUT
#define BUMPER PIN_A4 // Senzor na cihlu
 
#define DIAG_SERVO PIN_B3 // Propojka pro diagnosticky mod
#define DIAG_SENSORS PIN_B2 // Propojka pro diagnosticky mod
 
#DEFINE SOUND_HI PIN_A6 // komplementarni vystupy pro piezo pipak
#DEFINE SOUND_LO PIN_A7
 
char AXstring[40]; // Buffer pro prenos telemetrie
 
// makro pro PWM
#define GO(motor, direction, power) if(get_timer0()<=power) \
{direction##motor;} else {stop##motor;}
 
#int_TIMER2
void TIMER2_isr()
{
if (speed<255) speed+=INC_SPEED;
if (rovinka<MAX_ROVINKA) rovinka++;
if (dira<=T_DIRA) dira++;
if (cihla>0) cihla--;
}
// Primitivni Pipani
void beep(unsigned int16 period, unsigned int16 length)
{
unsigned int16 nn;
 
for(nn=length; nn>0; nn--)
{
output_high(SOUND_HI);output_low(SOUND_LO);
delay_us(period);
output_high(SOUND_LO);output_low(SOUND_HI);
delay_us(period);
}
}
/******************************************************************************/
void diagnostika()
{
unsigned int16 n;
 
while (input(DIAG_SERVO)) // Propojka, ktera spousti diagnostiku
{
for (n=500; n<800; n+=100)
{
beep(n,n); //beep UP
};
Delay_ms(1000);
//zastav vse
STOPL; STOPR;
//pravy pas
FR; Delay_ms(1000); STOPR; Delay_ms(1000);
BR; Delay_ms(1000); STOPR; Delay_ms(1000);
Beep(880,100); Delay_ms(1000);
//levy pas
FL; Delay_ms(1000); STOPL; Delay_ms(1000);
BL; Delay_ms(1000); STOPL; Delay_ms(1000);
Beep(880,100); Delay_ms(1000);
//oba pasy
FL; FR; Delay_ms(1000); STOPL; STOPR; Delay_ms(1000);
BL; BR; Delay_ms(1000); STOPL; STOPR; Delay_ms(1000);
};
while (input(DIAG_SENSORS))
{
int ls, rs;
while(!input(BUMPER)){beep(1100,100); Delay_ms(50);}
set_adc_channel(RSENSOR);
Delay_us(20);
rs=read_adc();
set_adc_channel(LSENSOR);
Delay_us(20);
ls=read_adc();
sprintf(AXstring,"L: %U R: %U\0", ls, rs); // Convert DATA to String.
SendPacket(&AXstring[0]);
delay_ms(1000);
};
}
///////////////////////////////////////////////////////////////////////////////
void cikcak()
{
unsigned int16 n;
 
line = RSENSOR; // cteni senzoru na caru
line |= LSENSOR << 1;
if (line!=0) return;
 
n=0;
switch(movement) // podivej se na druhou stranu nez se jelo
{
case L:
FL;BR;
movement=R;
break;
case R:
FR;BL;
movement=L;
break;
case S:
FL;BR;
movement=R;
n=CIK_CAK/2;
break;
}
while (0==(RSENSOR|LSENSOR)) // zkontroluj caru
{
if (n==CIK_CAK) // zmen smer zataceni
{
n=0;
switch(movement)
{
case L:
FL;BR;
movement=R;
break;
case R:
FR;BL;
movement=L;
break;
}
}
n++;
}
switch(movement)
{
case L:
FL;BR;
movement=R;
break;
case R:
FR;BL;
movement=L;
break;
}
Delay_ms(50);
STOPL;STOPR; // nasli jsme caru
line=S;
}
///////////////////////////////////////////////////////////////////////////////
void objizdka() // objede cihlu
{
unsigned int16 n;
 
BL;BR;Delay_ms(200);
STOPR;STOPL;
beep(900,1000);
movement=S;
cikcak();
 
BR; FL; Delay_ms(215); // otoc se 70° do prava
 
FR; FL; Delay_ms(600); // popojed rovne
 
BL; Delay_ms(50); // otoc se 90° do leva
STOPL; FR; Delay_ms(550);
 
FR; FL; Delay_ms(100); // popojed rovne na slepo
for(n=600;n>0;n--) // popojed rovne ale kontroluj caru
{
line = RSENSOR; // cteni senzoru na caru
line |= LSENSOR << 1;
if (line!=0) {Delay_ms(50); break;}
Delay_ms(1);
}
 
BR; // otoc se 60° do prava
for(n=600;n>0;n--)
{
line = RSENSOR; // cteni senzoru na caru
line |= LSENSOR << 1;
if (line!=0) break;
Delay_ms(1);
}
STOPR; STOPL;
 
movement=R;
cikcak();
cihla=T_DIRA;
dira=0;
}
///////////////////////////////////////////////////////////////////////////////
void prejeddiru() // vyresi diru
{
unsigned int16 n;
 
STOPL;STOPR;
beep(800,500);
switch (movement) //vrat se zpet na caru
{
case L:
for (n=COUVANI;n>0;n--) {GO(R,B,speed); Delay_ms(1);}
STOPL;STOPR;
break;
case R:
for (n=COUVANI;n>0;n--) {GO(L,B,speed); Delay_ms(1);}
STOPL;STOPR;
break;
case S:
goto sem;
break;
}
beep(800,500);
FR;FL; Delay_ms(PRES_DIRU); // popojedem dopredu mozna tam bude cara
sem:
STOPL; STOPR;
movement=S;
cikcak(); // najdi caru
cihla=T_DIRA;
dira=0;
}
///////////////////////////////////////////////////////////////////////////////
void main()
{
unsigned int16 n; // pro FOR
 
STOPL; STOPR; // prepne vystupy na ovladani motoru na output a zastavi
 
setup_oscillator(OSC_4MHZ|OSC_INTRC); // 4 MHz interni RC oscilator
 
port_b_pullups(TRUE); // pullups pro piano na diagnostiku
setup_spi(FALSE);
setup_timer_0(RTCC_INTERNAL|RTCC_DIV_1); // Casovac pro PWM
 
setup_timer_2(T2_DIV_BY_4,255,10); // Casovac pro regulaci
// preruseni kazdych 10ms
setup_adc_ports(sAN2|VSS_VDD); // nastaveni A/D prevodniku pro naraznik
setup_adc(ADC_CLOCK_INTERNAL);
set_adc_channel(2);
setup_timer_1(T1_INTERNAL|T1_DIV_BY_1); // Casovac pro naraznik
setup_ccp1(CCP_COMPARE_RESET_TIMER);
CCP_1=(2^10)-1; // prevod kazdou 1ms
 
setup_comparator(A0_VR_A1_VR); // inicializace komparatoru pro cidla cary
setup_vref(VREF_HIGH|TRESHOLD); // 32 kroku od 0.25 do 0.75 Vdd
 
Beep(1000,200); //double beep
Delay_ms(50);
Beep(1000,200);
Delay_ms(1000); // 1s
 
// povoleni rizeni rychlosti zataceni pres preruseni
enable_interrupts(INT_TIMER2);
enable_interrupts(GLOBAL);
 
/*---------------------------------------------------------------------------*/
sensors=S;
line=S;
last=S;
movement=S;
speed=FW_POMALU;
 
diagnostika();
cikcak(); // toc se, abys nasel caru
Delay_ms(500);
Beep(1000,200);
Delay_ms(500);
 
while(true) // hlavni smycka (jizda podle cary)
{
sensors = RSENSOR; // cteni senzoru na caru
sensors |= LSENSOR << 1;
 
if ((read_adc(ADC_READ_ONLY)<BUMPER_TRESHOLD) && (cihla==0)) objizdka();
 
switch (sensors) // zatacej podle toho, kde vidis caru
{
case S: // rovne
FL; FR; // pokud se jede dlouho rovne, tak pridej
dira=0;
movement=S;
continue;
case L: // trochu vlevo
GO(L, F, FW_POMALU+rovinka); GO(R, F, FW_STREDNE+rovinka);
line=L;
dira=0;
movement=L;
continue;
case R: // trochu vpravo
GO(R, F, FW_POMALU+rovinka); GO(L, F, FW_STREDNE+rovinka);
line=R;
dira=0;
movement=R;
continue;
default: // kdyz jsou obe cidla mimo caru, tak pokracuj dal
}
rovinka=0;
if (dira>=T_DIRA) prejeddiru();
if (last!=line) // pokud si prejel caru z jedne strany na druhou stranu, tak zabrzdi
{
last=line;
speed=FW_ZATACKA;
}
if (L==line) // kdyz jsou obe cidla mimo caru, zatoc na caru
{
STOPL;
GO(R, F, speed);
movement=L;
}
else
{
STOPR;
GO(L, F, speed);
movement=R;
}
} // while(true)
}
 
/roboti/istrobot/merkur/dokumentace/obrazky/PIC16F88/verze/vssver.scc
Cannot display: file marked as a binary type.
svn:mime-type = application/octet-stream
Property changes:
Added: svn:mime-type
+application/octet-stream
\ No newline at end of property
/roboti/istrobot/merkur/dokumentace/obrazky/PIC16F88/vssver.scc
Cannot display: file marked as a binary type.
svn:mime-type = application/octet-stream
Property changes:
Added: svn:mime-type
+application/octet-stream
\ No newline at end of property
/roboti/istrobot/merkur/dokumentace/obrazky/Thumbs.db
Cannot display: file marked as a binary type.
svn:mime-type = application/octet-stream
Property changes:
Added: svn:mime-type
+application/octet-stream
\ No newline at end of property
/roboti/istrobot/merkur/dokumentace/obrazky/vssver.scc
Cannot display: file marked as a binary type.
svn:mime-type = application/octet-stream
Property changes:
Added: svn:mime-type
+application/octet-stream
\ No newline at end of property
/roboti/istrobot/camerusII/HW/PCB/WhiteLEDPanel.pcb
Cannot display: file marked as a binary type.
svn:mime-type = application/octet-stream
Property changes:
Added: svn:mime-type
+application/octet-stream
\ No newline at end of property
/roboti/istrobot/camerusII/HW/WHITELEDPANEL.DSN
Cannot display: file marked as a binary type.
svn:mime-type = application/octet-stream
Property changes:
Added: svn:mime-type
+application/octet-stream
\ No newline at end of property
/roboti/istrobot/camerusII/HW/WHITELEDPANEL.asc
0,0 → 1,49
*PADS-PCB*
*PART*
D1 LED,LED5mm@LED5
D10 LED,LED5mm@LED5
D2 LED,LED5mm@LED5
D3 LED,LED5mm@LED5
D4 LED,LED5mm@LED5
D5 LED,LED5mm@LED5
D6 LED,LED5mm@LED5
D7 LED,LED5mm@LED5
D8 LED,LED5mm@LED5
D9 LED,LED5mm@LED5
J1 SCW2,ARK210/2@ARK210/2
J2 UNIPAD2,UNIPAD2@UNIPAD2
M1 PAD,HOLE_M3@HOLE_M3
M2 PAD,HOLE_M3@HOLE_M3
M3 PAD,HOLE_M3@HOLE_M3
M4 PAD,HOLE_M3@HOLE_M3
P1 R-TRIM,100@PT6V
R1 R,20@RL090
 
*NET*
*SIGNAL* N00284
D2.A D1.C
*SIGNAL* N00288
D2.C D3.A
*SIGNAL* N00294
D3.C D4.A
*SIGNAL* N00302
D4.C D5.A
*SIGNAL* N00312
D5.C D6.A
*SIGNAL* N00324
D6.C D7.A
*SIGNAL* N00338
D7.C D8.A
*SIGNAL* N00354
D8.C D9.A
*SIGNAL* N00372
D9.C D10.A
*SIGNAL* N00482
P1.3 D10.C J2.1 J2.2 P1.1
*SIGNAL* N00504
P1.2 R1.1
*SIGNAL* VCC
D1.A J1.2
*SIGNAL* GND
R1.2 M2.1 M3.1 J1.1 M1.1 M4.1
*END*
/roboti/istrobot/laserus/problem.txt
0,0 → 1,4
- nepodařilo se vyřešit snímání čáry ani jednou ze dvou typů čteček čárových kódů.
-čtečka nedokáže za phybu dostatečně přesně rozmítat laser. Proto dochází k automatickému vypnutí při prní chybě čtení.
-AGC (Automatic Gain Control) zabudované ve čtečce vyhodnotí za určitých případů čáru jako šum. Zvláště při najetí na čáru šikmo tak, že čára přetíná světelnou stopu ve větší délce, AGC pak dorovná celkový jas a čára se na datovém výstupu čidla ztratí.
/roboti/istrobot/laserus/SW/PIC/873/Reg.H
0,0 → 1,298
// Komplete definition of all Special Feature Registers
// of PIC16F87 and PIC16F88
// (c)miho 2005
 
#nolist
 
// SFR Registers in Memory Bank 0
#byte INDF = 0x00
#byte TMR0 = 0x01
#byte PCL = 0x02
#byte STATUS = 0x03
#bit IRP = STATUS.7
#bit RP1 = STATUS.6
#bit RP0 = STATUS.5
#bit TO = STATUS.4
#bit PD = STATUS.3
#bit Z = STATUS.2
#bit DC = STATUS.1
#bit C = STATUS.0
#byte FSR = 0x04
#byte PORTA = 0x05
#byte PORTB = 0x06
#byte PCLATH = 0x0A
#byte INTCON = 0x0B
#bit GIE = INTCON.7
#bit PEIE = INTCON.6
#bit TMR0IE = INTCON.5
#bit INT0IE = INTCON.4
#bit RBIE = INTCON.3
#bit TMR0IF = INTCON.2
#bit INT0IF = INTCON.1
#bit RBIF = INTCON.0
#byte PIR1 = 0x0C
#bit ADIF = PIR1.6
#bit RCIF = PIR1.5
#bit TXIF = PIR1.4
#bit SSPIF = PIR1.3
#bit CCP1IF = PIR1.2
#bit TMR2IF = PIR1.1
#bit TMR1IF = PIR1.0
#byte PIR2 = 0x0D
#bit OSFIF = PIR2.7
#bit CMIF = PIR2.6
#bit EEIF = PIR2.4
#byte TMR1L = 0x0E
#byte TMR1H = 0x0F
#byte T1CON = 0x10
#bit T1RUN = T1CON.6
#bit T1CKPS1 = T1CON.5
#bit T1CKPS0 = T1CON.4
#bit T1OSCEN = T1CON.3
#bit T1SYNC = T1CON.2
#bit TMR1CS = T1CON.1
#bit TMR1ON = T1CON.0
#byte TMR2 = 0x11
#byte T2CON = 0x12
#bit TOUTPS3 = T2CON.6
#bit TOUTPS2 = T2CON.5
#bit TOUTPS1 = T2CON.4
#bit TOUTPS0 = T2CON.3
#bit TMR2ON = T2CON.2
#bit T2CKPS1 = T2CON.1
#bit T2CKPS0 = T2CON.0
#byte SSPBUF = 0x13
#byte SSPCON1 = 0x14
#bit WCOL = SSPCON1.7
#bit SSPOV = SSPCON1.6
#bit SSPEN = SSPCON1.5
#bit CKP = SSPCON1.4
#bit SSPM3 = SSPCON1.3
#bit SSPM2 = SSPCON1.2
#bit SSPM1 = SSPCON1.1
#bit SSPM0 = SSPCON1.0
#byte CCPR1L = 0x15
#byte CCPR1H = 0x16
#byte CCP1CON = 0x17
#bit CCP1X = CCP1CON.5
#bit CCP1Y = CCP1CON.4
#bit CCP1M3 = CCP1CON.3
#bit CCP1M2 = CCP1CON.2
#bit CCP1M1 = CCP1CON.1
#bit CCP1M0 = CCP1CON.0
#byte RCSTA = 0x18
#bit SPEN = RCSTA.7
#bit RX9 = RCSTA.6
#bit SREN = RCSTA.5
#bit CREN = RCSTA.4
#bit ADDEN = RCSTA.3
#bit FERR = RCSTA.2
#bit OERR = RCSTA.1
#bit RX9D = RCSTA.0
#byte TXREG = 0x19
#byte RCREG = 0x1A
#byte ADRESH = 0x1E // F88 only
#byte ADCON0 = 0x1F // F88 only
#bit ADCS1 = ADCON0.7
#bit ADCS0 = ADCON0.6
#bit CHS2 = ADCON0.5
#bit CHS1 = ADCON0.4
#bit CHS0 = ADCON0.3
#bit GO = ADCON0.2
#bit ADON = ADCON0.0
 
// SFR Registers in Memory Bank 1
#byte INDF_1 = 0x80 // miror
#byte OPTION = 0x81
#bit RBPU = OPTION.7
#bit INTEDG = OPTION.6
#bit T0CS = OPTION.5
#bit T0SE = OPTION.4
#bit PSA = OPTION.3
#bit PS2 = OPTION.2
#bit PS1 = OPTION.1
#bit PS0 = OPTION.0
#byte PCL = 0x82
#byte STATUS_1 = 0x83 // mirror
#bit IRP_1 = STATUS_1.7
#bit RP1_1 = STATUS_1.6
#bit RP0_1 = STATUS_1.5
#bit TO_1 = STATUS_1.4
#bit PD_1 = STATUS_1.3
#bit Z_1 = STATUS_1.2
#bit DC_1 = STATUS_1.1
#bit C_1 = STATUS_1.0
#byte FSR = 0x84
#byte TRISA = 0x85
#byte TRISB = 0x86
#byte PCLATH_1 = 0x8A // mirror
#byte INTCON_1 = 0x8B // mirror
#bit GIE_1 = INTCON_1.7
#bit PEIE_1 = INTCON_1.6
#bit TMR0IE_1 = INTCON_1.5
#bit INT0IE_1 = INTCON_1.4
#bit RBIE_1 = INTCON_1.3
#bit TMR0IF_1 = INTCON_1.2
#bit INT0IF_1 = INTCON_1.1
#bit RBIF_1 = INTCON_1.0
#byte PIE1 = 0x8C
#bit ADIE = PIE1.6
#bit RCIE = PIE1.5
#bit TXIE = PIE1.4
#bit SSPIE = PIE1.3
#bit CCP1IE = PIE1.2
#bit TMR2IE = PIE1.1
#bit TMR1IE = PIE1.0
#byte PIE2 = 0x8D
#bit OSFIE = PIE2.7
#bit CMIE = PIE2.6
#bit EEIE = PIE2.4
#byte PCON = 0x8E
#bit POR = PCON.1
#bit BOR = PCON.0
#byte OSCCON = 0x8F
#bit IRCF2 = OSCCON.6
#bit IRCF1 = OSCCON.5
#bit IRCF0 = OSCCON.4
#bit OSTS = OSCCON.3
#bit IOFS = OSCCON.2
#bit SCS1 = OSCCON.1
#bit SCS0 = OSCCON.0
#byte OSCTUNE = 0x90
#bit TUN5 = OSCTUNE.5
#bit TUN4 = OSCTUNE.4
#bit TUN3 = OSCTUNE.3
#bit TUN2 = OSCTUNE.2
#bit TUN1 = OSCTUNE.1
#bit TUN0 = OSCTUNE.0
#byte PR2 = 0x92
#byte SSPADD = 0x93
#byte SSPSTAT = 0x94
#bit SMP = SSPSTAT.7
#bit CKE = SSPSTAT.6
#bit DA = SSPSTAT.5
#bit P = SSPSTAT.4
#bit S = SSPSTAT.3
#bit RW = SSPSTAT.2
#bit UA = SSPSTAT.1
#bit BF = SSPSTAT.0
#byte TXSTA = 0x98
#bit CSRC = TXSTA.7
#bit TX9 = TXSTA.6
#bit TXEN = TXSTA.5
#bit SYNC = TXSTA.4
#bit BRGH = TXSTA.2
#bit TRMT = TXSTA.1
#bit TX9D = TXSTA.0
#byte SPBRG = 0x99
#byte ANSEL = 0x9B // F88 only
#bit ANS6 = ANSEL.6
#bit ANS5 = ANSEL.5
#bit ANS4 = ANSEL.4
#bit ANS3 = ANSEL.3
#bit ANS2 = ANSEL.2
#bit ANS1 = ANSEL.1
#bit ANS0 = ANSEL.0
#byte CMCON = 0x9C
// #bit C2OUT = CMCON.7
// #bit C1OUT = CMCON.6
#bit C2INV = CMCON.5
#bit C1INV = CMCON.4
#bit CIS = CMCON.3
#bit CM2 = CMCON.2
#bit CM1 = CMCON.1
#bit CM0 = CMCON.0
#byte CVRCON = 0x9D
#bit CVREN = CVRCON.7
#bit CVROE = CVRCON.6
#bit CVRR = CVRCON.5
#bit CVR3 = CVRCON.3
#bit CVR2 = CVRCON.2
#bit CVR1 = CVRCON.1
#bit CVR0 = CVRCON.0
#byte ADRESL = 0x9E // F88 only
#byte ADCON1 = 0x9F // F88 only
#bit ADFM = ADCON1.7
#bit ADCS2 = ADCON1.6
#bit VCFG1 = ADCON1.5
#bit VCFG0 = ADCON1.4
 
// SFR Registers in Memory Bank 2
#byte INDF_2 = 0x100 // mirror
#byte TMR0_2 = 0x101 // mirror
#byte PCL_2 = 0x102 // mirror
#byte STATUS_2 = 0x103 // mirror
#bit IRP_2 = STATUS_2.7
#bit RP1_2 = STATUS_2.6
#bit RP0_2 = STATUS_2.5
#bit TO_2 = STATUS_2.4
#bit PD_2 = STATUS_2.3
#bit Z_2 = STATUS_2.2
#bit DC_2 = STATUS_2.1
#bit C_2 = STATUS_2.0
#byte FSR_2 = 0x104 // mirror
#byte WDTCON = 0x105
#bit WDTPS3 = WDTCON.4
#bit WDTPS2 = WDTCON.3
#bit WDTPS1 = WDTCON.2
#bit WDTPS0 = WDTCON.1
#bit SWDTEN = WDTCON.0
#byte PORTB_2 = 0x106 // mirror
#byte PCLATH_2 = 0x10A // mirror
#byte INTCON_2 = 0x10B // mirror
#bit GIE_2 = INTCON_2.7
#bit PEIE_2 = INTCON_2.6
#bit TMR0IE_2 = INTCON_2.5
#bit INT0IE_2 = INTCON_2.4
#bit RBIE_2 = INTCON_2.3
#bit TMR0IF_2 = INTCON_2.2
#bit INT0IF_2 = INTCON_2.1
#bit RBIF_2 = INTCON_2.0
#byte EEDATA = 0x10C
#byte EEADR = 0x10D
#byte EEDATH = 0x10E
#byte EEADRH = 0x10F
 
// SFR Registers in Memory Bank 3
#byte INDF_3 = 0x180 // mirror
#byte OPTION_3 = 0x181 // mirror
#bit RBPU_3 = OPTION_3.7
#bit INTEDG_3 = OPTION_3.6
#bit T0CS_3 = OPTION_3.5
#bit T0SE_3 = OPTION_3.4
#bit PSA_3 = OPTION_3.3
#bit PS2_3 = OPTION_3.2
#bit PS1_3 = OPTION_3.1
#bit PS0_3 = OPTION_3.0
#byte PCL_3 = 0x182 // mirror
#byte STATUS_3 = 0x183 // mirror
#bit IRP_3 = STATUS_3.7
#bit RP1_3 = STATUS_3.6
#bit RP0_3 = STATUS_3.5
#bit TO_3 = STATUS_3.4
#bit PD_3 = STATUS_3.3
#bit Z_3 = STATUS_3.2
#bit DC_3 = STATUS_3.1
#bit C_3 = STATUS_3.0
#byte FSR_3 = 0x184 // mirror
#byte TRISB_3 = 0x186 // mirror
#byte PLATH_3 = 0x18A // mirror
#byte INTCON_3 = 0x18B // mirror
#bit GIE_3 = INTCON_3.7
#bit PEIE_3 = INTCON_3.6
#bit TMR0IE_3 = INTCON_3.5
#bit INT0IE_3 = INTCON_3.4
#bit RBIE_3 = INTCON_3.3
#bit TMR0IF_3 = INTCON_3.2
#bit INT0IF_3 = INTCON_3.1
#bit RBIF_3 = INTCON_3.0
#byte EECON1 = 0x18C
#bit EEPGD = EECON1.7
#bit FREE = EECON1.4
#bit WRERR = EECON1.3
#bit WREN = EECON1.2
#bit WR = EECON1.1
#bit RD = EECON1.0
#byte EECON2 = 0x18D
 
#list
/roboti/istrobot/laserus/SW/PIC/873/laserus.PJT
0,0 → 1,40
[PROJECT]
Target=laserus.HEX
Development_Mode=
Processor=0x873F
ToolSuite=CCS
 
[Directories]
Include=C:\Program Files\PICC\devices\;C:\Program Files\PICC\Dr
Library=
LinkerScript=
 
[Target Data]
FileList=C:\PIC\laserus\873\laserus.c
BuildTool=C-COMPILER
OptionString=+FM
AdditionalOptionString=
BuildRequired=1
 
[laserus.c]
Type=4
Path=
FileList=
BuildTool=
OptionString=
AdditionalOptionString=
 
[mru-list]
1=laserus.c
 
[Windows]
0=0000 laserus.c 0 0 796 451 3 0
 
[Opened Files]
1=C:\PIC\laserus\873\laserus.c
2=C:\PIC\laserus\873\laserus.h
3=C:\Program Files\PICC\devices\16F873.h
4=
[Units]
Count=1
1=C:\PIC\laserus\873\laserus.c (main)
/roboti/istrobot/laserus/SW/PIC/873/laserus.c
0,0 → 1,130
#include "laserus.h"
 
#define SERVO PIN_B5 // Vystup pro rizeni serva
#define LASER PIN_B4 // Vstup pro cteni laseru
 
#define MOT_DIR_L PIN_C0 // Rizeni smeru otaceni motoru
#define MOT_DIR_R PIN_C3
 
// kroutitka
#define CERVENA 0 // AN0
#define CERNA 1 // AN1
//#define ZELENA 3 // AN3
//#define MODRA 4 // AN4
 
#byte INTCON = 0x0B // Interrupt configuration register
#bit GIE = INTCON.7
#bit PEIE = INTCON.6
#bit TMR0IE = INTCON.5
#bit INT0IE = INTCON.4
#bit RBIE = INTCON.3
#bit TMR0IF = INTCON.2
#bit INT0IF = INTCON.1
#bit RBIF = INTCON.0
 
boolean edge;
int8 uhel, olduhel;
int16 uhel16;
 
#int_EXT
EXT_isr()
{
int n, t1, t2, t;
 
set_timer0(0); // Vynulovani casovace pro 2ms
output_high(SERVO);
while(get_timer0()<(1000/256)); // Ceka 1ms
for(n=uhel; n>0; n--) delay_us(3); // Sirka impulzu podle uhlu
output_low(SERVO);
while(get_timer0()<(3000/256)); // Ceka do 3ms, nez zacne scanovat
 
set_timer0(0); // Vynulovani casovace pro zjisteni polohy cary
if(edge) // Zrcatko prejizdelo tam nebo zpet?
{
edge=false;
ext_int_edge(H_TO_L); // Pristi inerrupt bude od opacne hrany
INT0IF=0; // Povoleni dalsiho preruseni
enable_interrupts(INT_EXT);
enable_interrupts(GLOBAL);
// do
{
while(0==input(LASER)); // Ceka na detekci cary
// output_high(SERVO);
t1=get_timer0(); // Poznamena cas nabezne hrany
while(1==input(LASER)); // Ceka az zkonci cara
// output_low(SERVO);
t2=get_timer0(); // Poznamena cas sestupne hrany
t=t2-t1;
} while((t<3) || (t>20)); // Cara je detekovana, kdyz trva mezi xx ms
// if ((t>3) && (t<20)) uhel=(160-(read_adc()>>2))-t1;
// if (abs(olduhel-uhel)<40)
{
uhel=(160-(read_adc()>>2))-t1;
olduhel=uhel;
};
// uhel16=uhel;
// set_pwm1_duty(250-(uhel16<<2)); // Elektronicky diferencial
// set_pwm2_duty((uhel16));
set_adc_channel(CERNA);
}
else
{
edge=true;
ext_int_edge(L_TO_H); // Pristi inerrupt bude od opacne hrany
INT0IF=0; // Povoleni dalsiho preruseni
enable_interrupts(INT_EXT);
enable_interrupts(GLOBAL);
// do
{
while(0==input(LASER)); // Ceka na detekci cary
t1=get_timer0(); // Poznamena cas nabezne hrany
while(1==input(LASER)); // Ceka az zkonci cara
t2=get_timer0(); // Poznamena cas sestupne hrany
t=t2-t1;
} while((t<3) || (t>20)); // Cara je detekovana, kdyz trva mezi xx ms
if (abs(olduhel-uhel)<40)
{
// uhel=((read_adc()>>2)+32)+t1;
// olduhel=uhel;
};
set_adc_channel(CERVENA);
}
while(true);
}
 
 
 
void main()
{
 
setup_adc_ports(ALL_ANALOG); // Analogove vstupy pro cteni trimru
setup_adc(ADC_CLOCK_INTERNAL);
setup_spi(FALSE);
setup_timer_0(RTCC_INTERNAL|RTCC_DIV_256); // Casovac pro cteni laseru
setup_timer_1(T1_DISABLED);
setup_timer_2(T2_DIV_BY_4,255,1); // Casovac pro PWM cca 900Hz
setup_ccp1(CCP_PWM); // Nastaveni PWM pro diferencial RC1, RC2
setup_ccp2(CCP_PWM);
 
set_pwm1_duty(90); // Zastaveni PWM
set_pwm2_duty(90);
 
delay_ms(100);
set_adc_channel(CERVENA);
Delay_ms(1);
 
ext_int_edge(L_TO_H);
edge=true;
uhel=((read_adc()>>2)+32)+30;
olduhel=uhel;
 
enable_interrupts(INT_EXT);
enable_interrupts(GLOBAL);
 
delay_ms(1000);
 
output_high(MOT_DIR_L); // Oba motory vpred
output_high(MOT_DIR_R);
 
while(true);
}
/roboti/istrobot/laserus/SW/PIC/873/laserus.h
0,0 → 1,15
#include <16F873.h>
#device adc=8
 
#FUSES NOWDT //No Watch Dog Timer
#FUSES XT //Crystal osc <= 4mhz
#FUSES NOPUT //No Power Up Timer
#FUSES NOPROTECT //Code not protected from reading
#FUSES NOBROWNOUT //No brownout reset
#FUSES NOLVP //No low voltage prgming, B3(PIC16) or B5(PIC18) used for I/O
#FUSES NOCPD //No EE protection
#FUSES NOWRT //Program memory not write protected
#FUSES NODEBUG //No Debug mode for ICD
 
#use delay(clock=4000000)
 
/roboti/istrobot/laserus/SW/PIC/88/16F88_Reg.H
0,0 → 1,298
// Komplete definition of all Special Feature Registers
// of PIC16F87 and PIC16F88
// (c)miho 2005
 
#nolist
 
// SFR Registers in Memory Bank 0
#byte INDF = 0x00
#byte TMR0 = 0x01
#byte PCL = 0x02
#byte STATUS = 0x03
#bit IRP = STATUS.7
#bit RP1 = STATUS.6
#bit RP0 = STATUS.5
#bit TO = STATUS.4
#bit PD = STATUS.3
#bit Z = STATUS.2
#bit DC = STATUS.1
#bit C = STATUS.0
#byte FSR = 0x04
#byte PORTA = 0x05
#byte PORTB = 0x06
#byte PCLATH = 0x0A
#byte INTCON = 0x0B
#bit GIE = INTCON.7
#bit PEIE = INTCON.6
#bit TMR0IE = INTCON.5
#bit INT0IE = INTCON.4
#bit RBIE = INTCON.3
#bit TMR0IF = INTCON.2
#bit INT0IF = INTCON.1
#bit RBIF = INTCON.0
#byte PIR1 = 0x0C
#bit ADIF = PIR1.6
#bit RCIF = PIR1.5
#bit TXIF = PIR1.4
#bit SSPIF = PIR1.3
#bit CCP1IF = PIR1.2
#bit TMR2IF = PIR1.1
#bit TMR1IF = PIR1.0
#byte PIR2 = 0x0D
#bit OSFIF = PIR2.7
#bit CMIF = PIR2.6
#bit EEIF = PIR2.4
#byte TMR1L = 0x0E
#byte TMR1H = 0x0F
#byte T1CON = 0x10
#bit T1RUN = T1CON.6
#bit T1CKPS1 = T1CON.5
#bit T1CKPS0 = T1CON.4
#bit T1OSCEN = T1CON.3
#bit T1SYNC = T1CON.2
#bit TMR1CS = T1CON.1
#bit TMR1ON = T1CON.0
#byte TMR2 = 0x11
#byte T2CON = 0x12
#bit TOUTPS3 = T2CON.6
#bit TOUTPS2 = T2CON.5
#bit TOUTPS1 = T2CON.4
#bit TOUTPS0 = T2CON.3
#bit TMR2ON = T2CON.2
#bit T2CKPS1 = T2CON.1
#bit T2CKPS0 = T2CON.0
#byte SSPBUF = 0x13
#byte SSPCON1 = 0x14
#bit WCOL = SSPCON1.7
#bit SSPOV = SSPCON1.6
#bit SSPEN = SSPCON1.5
#bit CKP = SSPCON1.4
#bit SSPM3 = SSPCON1.3
#bit SSPM2 = SSPCON1.2
#bit SSPM1 = SSPCON1.1
#bit SSPM0 = SSPCON1.0
#byte CCPR1L = 0x15
#byte CCPR1H = 0x16
#byte CCP1CON = 0x17
#bit CCP1X = CCP1CON.5
#bit CCP1Y = CCP1CON.4
#bit CCP1M3 = CCP1CON.3
#bit CCP1M2 = CCP1CON.2
#bit CCP1M1 = CCP1CON.1
#bit CCP1M0 = CCP1CON.0
#byte RCSTA = 0x18
#bit SPEN = RCSTA.7
#bit RX9 = RCSTA.6
#bit SREN = RCSTA.5
#bit CREN = RCSTA.4
#bit ADDEN = RCSTA.3
#bit FERR = RCSTA.2
#bit OERR = RCSTA.1
#bit RX9D = RCSTA.0
#byte TXREG = 0x19
#byte RCREG = 0x1A
#byte ADRESH = 0x1E // F88 only
#byte ADCON0 = 0x1F // F88 only
#bit ADCS1 = ADCON0.7
#bit ADCS0 = ADCON0.6
#bit CHS2 = ADCON0.5
#bit CHS1 = ADCON0.4
#bit CHS0 = ADCON0.3
#bit GO = ADCON0.2
#bit ADON = ADCON0.0
 
// SFR Registers in Memory Bank 1
#byte INDF_1 = 0x80 // miror
#byte OPTION = 0x81
#bit RBPU = OPTION.7
#bit INTEDG = OPTION.6
#bit T0CS = OPTION.5
#bit T0SE = OPTION.4
#bit PSA = OPTION.3
#bit PS2 = OPTION.2
#bit PS1 = OPTION.1
#bit PS0 = OPTION.0
#byte PCL = 0x82
#byte STATUS_1 = 0x83 // mirror
#bit IRP_1 = STATUS_1.7
#bit RP1_1 = STATUS_1.6
#bit RP0_1 = STATUS_1.5
#bit TO_1 = STATUS_1.4
#bit PD_1 = STATUS_1.3
#bit Z_1 = STATUS_1.2
#bit DC_1 = STATUS_1.1
#bit C_1 = STATUS_1.0
#byte FSR = 0x84
#byte TRISA = 0x85
#byte TRISB = 0x86
#byte PCLATH_1 = 0x8A // mirror
#byte INTCON_1 = 0x8B // mirror
#bit GIE_1 = INTCON_1.7
#bit PEIE_1 = INTCON_1.6
#bit TMR0IE_1 = INTCON_1.5
#bit INT0IE_1 = INTCON_1.4
#bit RBIE_1 = INTCON_1.3
#bit TMR0IF_1 = INTCON_1.2
#bit INT0IF_1 = INTCON_1.1
#bit RBIF_1 = INTCON_1.0
#byte PIE1 = 0x8C
#bit ADIE = PIE1.6
#bit RCIE = PIE1.5
#bit TXIE = PIE1.4
#bit SSPIE = PIE1.3
#bit CCP1IE = PIE1.2
#bit TMR2IE = PIE1.1
#bit TMR1IE = PIE1.0
#byte PIE2 = 0x8D
#bit OSFIE = PIE2.7
#bit CMIE = PIE2.6
#bit EEIE = PIE2.4
#byte PCON = 0x8E
#bit POR = PCON.1
#bit BOR = PCON.0
#byte OSCCON = 0x8F
#bit IRCF2 = OSCCON.6
#bit IRCF1 = OSCCON.5
#bit IRCF0 = OSCCON.4
#bit OSTS = OSCCON.3
#bit IOFS = OSCCON.2
#bit SCS1 = OSCCON.1
#bit SCS0 = OSCCON.0
#byte OSCTUNE = 0x90
#bit TUN5 = OSCTUNE.5
#bit TUN4 = OSCTUNE.4
#bit TUN3 = OSCTUNE.3
#bit TUN2 = OSCTUNE.2
#bit TUN1 = OSCTUNE.1
#bit TUN0 = OSCTUNE.0
#byte PR2 = 0x92
#byte SSPADD = 0x93
#byte SSPSTAT = 0x94
#bit SMP = SSPSTAT.7
#bit CKE = SSPSTAT.6
#bit DA = SSPSTAT.5
#bit P = SSPSTAT.4
#bit S = SSPSTAT.3
#bit RW = SSPSTAT.2
#bit UA = SSPSTAT.1
#bit BF = SSPSTAT.0
#byte TXSTA = 0x98
#bit CSRC = TXSTA.7
#bit TX9 = TXSTA.6
#bit TXEN = TXSTA.5
#bit SYNC = TXSTA.4
#bit BRGH = TXSTA.2
#bit TRMT = TXSTA.1
#bit TX9D = TXSTA.0
#byte SPBRG = 0x99
#byte ANSEL = 0x9B // F88 only
#bit ANS6 = ANSEL.6
#bit ANS5 = ANSEL.5
#bit ANS4 = ANSEL.4
#bit ANS3 = ANSEL.3
#bit ANS2 = ANSEL.2
#bit ANS1 = ANSEL.1
#bit ANS0 = ANSEL.0
#byte CMCON = 0x9C
// #bit C2OUT = CMCON.7
// #bit C1OUT = CMCON.6
#bit C2INV = CMCON.5
#bit C1INV = CMCON.4
#bit CIS = CMCON.3
#bit CM2 = CMCON.2
#bit CM1 = CMCON.1
#bit CM0 = CMCON.0
#byte CVRCON = 0x9D
#bit CVREN = CVRCON.7
#bit CVROE = CVRCON.6
#bit CVRR = CVRCON.5
#bit CVR3 = CVRCON.3
#bit CVR2 = CVRCON.2
#bit CVR1 = CVRCON.1
#bit CVR0 = CVRCON.0
#byte ADRESL = 0x9E // F88 only
#byte ADCON1 = 0x9F // F88 only
#bit ADFM = ADCON1.7
#bit ADCS2 = ADCON1.6
#bit VCFG1 = ADCON1.5
#bit VCFG0 = ADCON1.4
 
// SFR Registers in Memory Bank 2
#byte INDF_2 = 0x100 // mirror
#byte TMR0_2 = 0x101 // mirror
#byte PCL_2 = 0x102 // mirror
#byte STATUS_2 = 0x103 // mirror
#bit IRP_2 = STATUS_2.7
#bit RP1_2 = STATUS_2.6
#bit RP0_2 = STATUS_2.5
#bit TO_2 = STATUS_2.4
#bit PD_2 = STATUS_2.3
#bit Z_2 = STATUS_2.2
#bit DC_2 = STATUS_2.1
#bit C_2 = STATUS_2.0
#byte FSR_2 = 0x104 // mirror
#byte WDTCON = 0x105
#bit WDTPS3 = WDTCON.4
#bit WDTPS2 = WDTCON.3
#bit WDTPS1 = WDTCON.2
#bit WDTPS0 = WDTCON.1
#bit SWDTEN = WDTCON.0
#byte PORTB_2 = 0x106 // mirror
#byte PCLATH_2 = 0x10A // mirror
#byte INTCON_2 = 0x10B // mirror
#bit GIE_2 = INTCON_2.7
#bit PEIE_2 = INTCON_2.6
#bit TMR0IE_2 = INTCON_2.5
#bit INT0IE_2 = INTCON_2.4
#bit RBIE_2 = INTCON_2.3
#bit TMR0IF_2 = INTCON_2.2
#bit INT0IF_2 = INTCON_2.1
#bit RBIF_2 = INTCON_2.0
#byte EEDATA = 0x10C
#byte EEADR = 0x10D
#byte EEDATH = 0x10E
#byte EEADRH = 0x10F
 
// SFR Registers in Memory Bank 3
#byte INDF_3 = 0x180 // mirror
#byte OPTION_3 = 0x181 // mirror
#bit RBPU_3 = OPTION_3.7
#bit INTEDG_3 = OPTION_3.6
#bit T0CS_3 = OPTION_3.5
#bit T0SE_3 = OPTION_3.4
#bit PSA_3 = OPTION_3.3
#bit PS2_3 = OPTION_3.2
#bit PS1_3 = OPTION_3.1
#bit PS0_3 = OPTION_3.0
#byte PCL_3 = 0x182 // mirror
#byte STATUS_3 = 0x183 // mirror
#bit IRP_3 = STATUS_3.7
#bit RP1_3 = STATUS_3.6
#bit RP0_3 = STATUS_3.5
#bit TO_3 = STATUS_3.4
#bit PD_3 = STATUS_3.3
#bit Z_3 = STATUS_3.2
#bit DC_3 = STATUS_3.1
#bit C_3 = STATUS_3.0
#byte FSR_3 = 0x184 // mirror
#byte TRISB_3 = 0x186 // mirror
#byte PLATH_3 = 0x18A // mirror
#byte INTCON_3 = 0x18B // mirror
#bit GIE_3 = INTCON_3.7
#bit PEIE_3 = INTCON_3.6
#bit TMR0IE_3 = INTCON_3.5
#bit INT0IE_3 = INTCON_3.4
#bit RBIE_3 = INTCON_3.3
#bit TMR0IF_3 = INTCON_3.2
#bit INT0IF_3 = INTCON_3.1
#bit RBIF_3 = INTCON_3.0
#byte EECON1 = 0x18C
#bit EEPGD = EECON1.7
#bit FREE = EECON1.4
#bit WRERR = EECON1.3
#bit WREN = EECON1.2
#bit WR = EECON1.1
#bit RD = EECON1.0
#byte EECON2 = 0x18D
 
#list
/roboti/istrobot/laserus/SW/PIC/88/laser.PJT
0,0 → 1,41
[PROJECT]
Target=laser.HEX
Development_Mode=
Processor=0x688F
ToolSuite=CCS
 
[Directories]
Include=C:\Program Files\PICC\devices\;C:\Program Files\PICC\Dr
Library=
LinkerScript=
 
[Target Data]
FileList=C:\PIC\laserus\laser.c
BuildTool=C-COMPILER
OptionString=+FM
AdditionalOptionString=
BuildRequired=1
 
[laser.c]
Type=4
Path=
FileList=
BuildTool=
OptionString=
AdditionalOptionString=
 
[mru-list]
1=laser.c
 
[Windows]
0=0000 laser.c 0 0 796 451 3 0
 
[Opened Files]
1=C:\PIC\laserus\laser.c
2=C:\PIC\laserus\laser.h
3=C:\Program Files\PICC\devices\16F88.h
4=C:\PIC\laserus\16F88_Reg.H
5=
[Units]
Count=1
1=C:\PIC\laserus\laser.c (main)
/roboti/istrobot/laserus/SW/PIC/88/laser.c
0,0 → 1,96
#include "laser.h"
#include "16F88_Reg.H"
 
#define SERVO PIN_B5 // Vystup pro rizeni serva
#define LASER PIN_B4 // Vstup pro cteni laseru
 
// kroutitka
#define CERVENA 0 // AN0
#define CERNA 1 // AN1
//#define ZELENA 3 // AN3
//#define MODRA 4 // AN4
 
//#define OFFSET 100 // Predni kolecko vprostred pri care vprostred
//#define HYSTERESE 3 // Rozdil mezi behem tam a zpet
 
boolean edge;
int8 uhel;
 
#int_EXT
EXT_isr()
{
int n, t1, t2, t;
 
set_timer0(0); // Vynulovani casovace pro 2ms
output_high(SERVO);
while(get_timer0()<(1000/256)); // Ceka 1ms
for(n=uhel; n>0; n--) delay_us(3); // Sirka impulzu podle uhlu
output_low(SERVO);
while(get_timer0()<(3000/256)); // Ceka do 3ms, nez zacne scanovat
 
set_timer0(0); // Vynulovani casovace pro zjisteni polohy cary
if(edge) // Zrcatko prejizdelo tam nebo zpet?
{
edge=false;
ext_int_edge(H_TO_L); // Pristi inerrupt bude od opacne hrany
INT0IF_1=0; // Povoleni dalsiho preruseni
enable_interrupts(INT_EXT);
enable_interrupts(GLOBAL);
// do
{
while(0==input(LASER)); // Ceka na detekci cary
// output_high(SERVO);
t1=get_timer0(); // Poznamena cas nabezne hrany
while(1==input(LASER)); // Ceka az zkonci cara
// output_low(SERVO);
t2=get_timer0(); // Poznamena cas sestupne hrany
t=t2-t1;
} //while((t<5) || (t>7)); // Cara je detekovana, kdyz trva mezi xx ms
if ((t>3) && (t<8)) uhel=(160-(read_adc()>>2))-t1;
set_adc_channel(1);
}
else
{
edge=true;
ext_int_edge(L_TO_H);
INT0IF_1=0; // Povoleni dalsiho preruseni
enable_interrupts(INT_EXT);
enable_interrupts(GLOBAL);
// do
{
while(0==input(LASER)); // Ceka na detekci cary
t1=get_timer0(); // Poznamena cas nabezne hrany
while(1==input(LASER)); // Ceka az zkonci cara
t2=get_timer0(); // Poznamena cas sestupne hrany
t=t2-t1;
} //while((t<5) || (t>7)); // Cara je detekovana, kdyz trva mezi xx ms
if ((t>3) && (t<8)) uhel=((read_adc()>>2)+32)+t1;
set_adc_channel(0);
}
while(true);
}
 
 
 
void main()
{
setup_adc_ports(sAN0|sAN1|VSS_VDD); // AD pro kroutitka
setup_adc(ADC_CLOCK_INTERNAL);
setup_spi(FALSE);
setup_timer_0(RTCC_INTERNAL|RTCC_DIV_256);
setup_timer_1(T1_DISABLED);
setup_timer_2(T2_DISABLED,0,1);
setup_comparator(NC_NC_NC_NC);
setup_vref(FALSE);
setup_oscillator(False);
 
delay_ms(100);
set_adc_channel(0);
Delay_ms(1);
 
ext_int_edge(L_TO_H);
edge=true;
uhel=((read_adc()>>2)+32)+30;;
enable_interrupts(INT_EXT);
enable_interrupts(GLOBAL);
}
/roboti/istrobot/laserus/SW/PIC/88/laser.h
0,0 → 1,18
#include <16F88.h>
#device adc=8
 
#FUSES NOWDT //No Watch Dog Timer
#FUSES XT //Crystal osc <= 4mhz
#FUSES NOPUT //No Power Up Timer
#FUSES MCLR //Master Clear pin enabled
#FUSES NOBROWNOUT //No brownout reset
#FUSES NOLVP //No low voltage prgming, B3(PIC16) or B5(PIC18) used for I/O
#FUSES NOCPD //No EE protection
#FUSES NOWRT //Program memory not write protected
#FUSES NODEBUG //No Debug mode for ICD
#FUSES NOPROTECT //Code not protected from reading
#FUSES NOFCMEN //Fail-safe clock monitor disabled
#FUSES NOIESO //Internal External Switch Over mode disabled
 
#use delay(clock=4000000)
 
/roboti/istrobot/laserus/DOC/Fotky/P1140012.JPG
Cannot display: file marked as a binary type.
svn:mime-type = application/octet-stream
Property changes:
Added: svn:mime-type
+application/octet-stream
\ No newline at end of property
/roboti/istrobot/laserus/DOC/Fotky/P1140013.JPG
Cannot display: file marked as a binary type.
svn:mime-type = application/octet-stream
Property changes:
Added: svn:mime-type
+application/octet-stream
\ No newline at end of property
/roboti/istrobot/laserus/DOC/Fotky/P1140014.JPG
Cannot display: file marked as a binary type.
svn:mime-type = application/octet-stream
Property changes:
Added: svn:mime-type
+application/octet-stream
\ No newline at end of property
/roboti/istrobot/laserus/DOC/Datasheets/-5400b.pdf
0,0 → 1,1245
+%âãÏÓ
+0000000016 00000 n
+0000000907 00000 n
+0000001200 00000 n
+0000001407 00000 n
+0000001569 00000 n
+0000001591 00000 n
+0000005034 00000 n
+0000005056 00000 n
+0000008229 00000 n
+0000008251 00000 n
+0000011780 00000 n
+0000011802 00000 n
+0000015523 00000 n
+0000015545 00000 n
+0000019173 00000 n
+0000019195 00000 n
+0000021980 00000 n
+0000022090 00000 n
+0000022195 00000 n
+0000023615 00000 n
+0000023637 00000 n
+0000028639 00000 n
+0000028661 00000 n
+0000032332 00000 n
+0000032409 00000 n
+0000032487 00000 n
+0000000962 00000 n
+0000001179 00000 n
+stream
+hI Ã÷ -Äò`1^ÖÊ W/0Ú0ðnf`žs€áaƒ¶7C°öµ ì
+stream
+€A ¡ˆ€Ò ŒqÈÈ\0ÃŒ<h ÇpÜ@r2ÀÊât$A
+…ˆòbTœ@j“‹†#!Ü@1…D²ì(É!ò9N
+ Æâá¤\kfEÍ°;Õò.1 †±d d1½Œæ˜ŒV3d„8æ Acïc
+žrùŸËèô±Ê¾ƒ‰EÆc™”Ó]”Øæöƒ<¶‡)ً·ºþ€ifÒj7Ã^\iEöü̝SۍÐÞ6Û/Ú¾÷l],½DsC†ýíõG×â÷íê#JŸ§·ÃŒøÕf?Ôô?ŽSüÅ&£æò7ÊÓöÃ@J«58NÂ<0€m O³Ï»ì9Ï3Øô¸ÎÓ="¡»Ñ7®zÄú¼T\èÄ®ld³F´<³Aîbfå8-Èhæ7’i†ŒK’Ð82CÍIŒëн†PÃLÏ‹Øjö0®ãé /rò9L‹ŒŽKòb÷ Ìï¼Ë
+¶’âöð¯ñÒ3K
+ž)¦;R.‰Y컬Z9
+5¸µJÔÚ#Ut©…´5÷
+‹3L"P˜É>Hdšy’¥YÐIƒ„M J“¬âIICŸ%¥+B“rªOJÙE+å! ”Æp…²ùVå²þ–é?<Ç #åd •Ò&X“'@™¥ü‘™RÞfLBS愵šs
+=<C5æTâ§Ri䥴Z¦‚#PfM$¨“¾¯U«Tªå>34‚¨ÔµÖà*ík¬Ä^´MZŒ ©m¬5m*ï^k¥n¥Ô ‚Ö
+W¯V¾X–ü͎ݒ±¶RÇÎù-Wì#²µúÌ‹Af흟åîMXkSM,µµ•²ÔU«Ul¥=Œ«3´ôÛ¬šì»¢µÚÌ[uZ+ì,¸·ÁV›~flÕ±çËË]mªež,VžéZ;”•.åu£¥ìÛK»PÛ©O³–æXë³jæ½í³–ÂÒ:óYîmĕ7Ê×®»|bÎÝP[—Š¦µû£r/þ¿—bž½ecxnm}±X?ÛËôb¯6´Šk ߚ:ÕnÂt
+NŽÎK
+D
+stream
+Éâè$²1Ž£Ò ¤Rn.JçpÉôºaB™A Ã)ԘkF¤I"Óù}‡3©Õa£Iµf›@˜Ñ,2XhÌAÊëtêõDi;—QíÐaÄRçh¨Z¥VÈĒár–à+ðIØʍ&á…ÃxMþ»i°D±ðф®R8­brøœîû„ÎÛë™j~.i’ÄG1Lþ†¹­»i±û(¤]¬ºà¶¸ˆâ)_´[Š$ˆaUâñä{k¦b¥šØäåŽV߃3çt;[[>]ŸìdœŽïWI! æÃX«·Éòó&~Ž$ó<î?.ûàù;!£þü8²È‘»!›iA/xh‘)ìí½¬Rìþ>pdé! 
+)Pì? DP”8ˆ†1D"×DŽÌZ”Ã/47!a¢õ§‘L`ƒÄ±ÐsF¯Ò GAÃÿ"ÀPœ€’É2\}ª±ÐoɑŸ²rĦ¢I
+G3õM¼ªâ8E›6âcGøÈo‹_8*NWö!‘ä~3ZW•=Ɣ^9*ao1™åñ*S Ö&Oç¹Å5˜CÖî}ŒÆqîM¢i5%(ª†1Ûï§^t®£!å¸L¾zŒ”íÄ92z…ëÏþá:îk¨ÊúÎ/ë²î§?à,~¢D ®Ñ'@›$ÒönŽÆý;BÛ’ê<#AÀíZí†øt‡1/Ãq›´<•·ÛÕÄ¢'|·6Õ.< ׿S«uwÐñÃzøòP’׿URÍ] Ìz.‡©}‹]h>hºsÛ'½Âj’¢ö"wâï~ƒ«g>Ì¿Z.²"ÆLªúø—Èùët“‰ü9Lƒ|³
+É"Š%ò%xÁß‹Ó Š$£@FBKãTQ¤êḡŸ±JÌ}ô9çø 3mi+?ø}#øÐ¡À¢Hàle„¥ðB¨dáo„Er¨…ÚŒkPò
+e•…£u†³Q8dcÒG³çfËhŒvk¦CƾÑ2E;‰5£ö½Û
+v.mÀ÷2Ÿ hioˆ•RF…ŠS<&a,, ®øfç™
+–2˜F†êHK³cWÏÙ•é¼á!v«³Ö{;?Ýa³ï}ÚÚ^ù—}8EôÉQ8׺ŠPM>¹:ݵ xÌÏCMÍhNàÒꗺå„n¿Üy;½ÒHÄÆ(ÀÛPÁsÂp«‘wkÝ9ñ ›Eü ƒü[…¼&ÅxQ
+¢ã‡n®CĈ?%ដ8þ4Âxç"Ýáßrn#Eï/müǔ;^t‘¹à5€ü¨ôðùúèÅ#šr#О‡DB|Ÿ¨=Ž’uºZ셼oª@áÖù‡]~K ¹N(­»)#é½£ª]>?Û:{¡{Í£´¸HsÐ;j}ìåHusßÚyÏ`ç}çŸx.ñÓãÏ{ñ
+jÞڐÜ~mv€
+ ÜΊ/v×Ë-Ɉ„0úÞðȧªW
+½jöê"qD‘â{çëh°¶qq^ÛBÚnelHm ¯„yѓ ~ÇbŽ`D!+¶$Ò ‚PÁ!Ä:ÿ¦ÎzlþyÃúÿ²"R¶Xh28ÐÄèmѶTÏ]%ƒ¿#¬p?¯^xòÏÃêWQ’­ˆY"È·¤
+fRN­ˆfiFÑ ‹rBÎß'dfòE(û°Œ Lþó¦K(ò C¦“*`*¬:EŽ¥)æHPž?RÁO‰,ñê¸ÊÂã2(l:ù/ ‹„K™.'ù-+A+¿&òîOŽH•3N @¡“
+¬'1´ÞÌV%s)óK…;2(?.ÅN!3-
+stream
+‡‹†²©dn: ÈfRI4æwžË¨ Î.›N"8ÄTk–Ïè3Àg
+ŒIÅÕIU^3>—РÔúˆe7ŠŽ#›Mp$¯Ù­×&µL™AÇ"ᅆr1†EFó{¥.Õw¯N¢v,D¨m~ºÓpQj–&6¨c-ë¶o'$¨4mo49ÁéãcxƀoXÑë°; Ê#7Ðh©[«^ iEaš–cI¯ÁfðèØÓ?JÖà8±4lf ‹±v~jƒîÇ#¿’ÿÍŽwà ¿†/îÌîð(l †>˛ró$Ž«úô"a¢tá=ë´
+’,Ž‡AA²1$®ò2,¢É²|•)§b›Ê{ªÃKRä®L„»)6òÊúLèÚÚ½ˆdΈ4ï 73ªÓªÁ6H³Êp„¾óš Óд£PŒ$å"Γý>J-›O G“jVÃR“#K§f‰ÒÎm:ÂPÒô°‡4]!/'MHÕ¨W#QÉ-VHR„ÖÒíq †ïõ^¦¡íQGG!!
+»1¤·Sèå”îG° bð¨²Cö­ÔaÄLñ7œÄZˆt`ÂhU½sʵS?–mà•Û)ÓÀ‹FPm‰tB·RÆõµÿRh³êñE1ò„Tl¬í~Ä2Š¿7ȃ¯Q`Êc‹ºn“Sca¶¶AX¶U9ŽÈªýu‘Îe–b×%båeSNh‡«óMP•ºùÔgg­=Œž]÷ýsX»è«Ûãõ–~ª¬–“[Z3ÔË9Øv£2V/¦‘¨P»
+ù®äÔâð‡,N ¡Üû.Öÿì{…þ¯ì˜p‰¢²Þ¯"îS‚¾m÷6ïµpAºU¿l—äÕÅ)þk¼ðPï’ÙÈJõÊê¼fío,KËòH5=t{ï1sô3T_Òq¼ÛÃ×õ].¿2Ù=¯¢¾Ü#ïƾûœGÈø 5éªíÍ&!KæŸÏȺÊq]ŒWW¥A~š"‰«éþ æJ—Ô)äÜó´²<+6 ðÖÞbß}ùü6=ñûL¯ÁÛ~žf5•cž„¢ÄseM¨ £
+ÙiÆŠÜ¢ïv’qT·i€“›ÖR%º•¼W!Øëµ=ëŠ]dB
+Ûë»/ų»''Þ¼gmÖ—¶æßÞzìa¯­Ý¦·Æûa;Õ_F±xe]¨ûCnæB‚Ð$Ûï1WÄÔ-Ub$7K±m—W'¦ËW™Žo±©WÆöDŸØ²ìý~!6œôZ ‡hì1 ³&Ôדíf{9FËáÃü߯Ò#ª¹bì奅éÉÆÌ3&Áb*díE‚¾èFÍÞ{á›/}T¤¸73NÓG~¯‘Ç7{_h o³õÛʗžêÚý©1
+'œî½?7:ËÞ¼
+ؖœ¸)Þ®»s‘q罧©/Ç8‘pR^]xHª–¥†çó^‚•ùç6ñý
+L/L­¿Kļo[·Í{/R±:á—þc¯{YpJ½çÌïí‚ ¯ã0Z
+stream
+‡¸Ôf.Œ„Ø, †ÃÆCA²+G#"èÜv>.Ã£)$.<
+@¡QÃZ¾œÎé’iõ#JÄ©Óù$Št.¬Õ)òXlìaFÅÃ
+²U<©
+àòFilÄÀQÊm¢ñÌ^‚¤/ô…Ȫ¼JÆHŒã¥ I+â¯-L›(JҔ¡Hˆ|-³È2!µq
+ËIl4Ì¥§1ŒA®4Å·.L‡¸s«Ÿ5Ï.ÛÁ¥Œ 3$P/«×²®Ò¤ÐªG'Ѭ
+5B@é[};Òë¼1<1rä 3§/ì'5Íã'5ËèkúÎRó´þÏr½TçL2r0>rC9%Wü›#õìÌÖé€üW¯L`žX¯lÙ²DP†XQ;'`×0£a^Ç ]fÆVóilYíCZBa0Â|íq0/ìä Z+LïZ¯ÜÿÀ5­€‡:Ð"BÎ;Á«8úD,JsƒÃSYeHCÙaÐîý»ˆÈ8¶(üO×1»øô M·E–ßäÒ$o”U–³Ÿ:å±\í=L1QXÀ¹³¯mPW-ÄØOؼ
+Fˆš
+aZ
+"+â)Àص'GP€È,LS*Yij„bÊ06F&"E·¦q¢ÒŽ+íª0¡§ å‹ÙJn±!î¾ØÖy+mˆŒõG3Á㱋lQÂ,Gg<ìbYœæTÏeë\Qê„EÓPTniùÇƗ$dŽ•ŽÅ˜èrø64L–PÊ3‘"Dif‚UÙB\‰Ô‰qzNÅÕ*Ñ¢´S—F+°øÁZ„‘Š'½C#ؗ1ÔD<òÖc¸Vi̧ŒE:Í3¬UQ*ÄåD³¢`fìÚ%÷N#˜‡ä)@œèV\¼t«/Ý"K‹)Vn%‘0"TQ•®‚}5ÙÕe3抲:8¹ÇÎå¤|ùrÒ.yDBÇTŠb®¾=‘¤±(²KŒ„±‚Έ‰G$oqó֑N3‘6\±,IóV•Ó‘ «7¤äîDºh¯œ±;xæ¢"S©!!J‘9Qq‚ ’ gOgŠ–rFŸEÊmS¢‰|¤§0·RӘ¨¤­#‡ò U§ýL×ü8ª0šŚ3 ¢Y…0>‰C
+q(dG“pµcI$d¹ 䩂0b[jå/b¹Nª^Oå‹R©­ijVY¡5ßµIJš”D‰¨ò,{̓.3ċ9=´ÈRÎÐÑ9 'Êu$ ‚ƒtàCLP&ܝ²ûbX­¢è|֐„:yøå­ë%•åúœ[qmW;ÿ·/õS\¦óà%¹ºéXÚÞDkÝl¶miz”åƒ5â=ß²uVïZöéu/1͸jîákÄNmú"½7Æ×=+nSÃðA õÍpiZ ˜ÄÿÒkÖF¦ÚG‹ñ~Áb¿1Ç9B J`5 Jó™%‡¤”pƒ.mÔ‚ FPñx Å ʃ21¶ ¥ G[vhMûp¥; I;âhÍpù"g^£‘cýÆșÌe<•qÚN‡ïÿ"ÉÊÄL2ítgÙf8Øupb_îf9¢£PswqÜn(ØñÞLw,ÖRÎ3H±fú®3Æ΋ó!#ø”Ü1@š—8_¡ê€
+Ô·²¼»[²ë2-Ë3ºfÛɹ·»~éÜ»·ÚîÁUíîù;Ü7ð¿ÁRúÔÕ; 벜[ч1Öñjïˏ¦‹á¾^žpgëçz·
+Ú¢PlÞ‰%w¦êûg°DîC×}vÖ몖Yi]<Èw®—÷kÝ4{:z}ô˜æ-{Ù<ÆõÖò3z³¨‡¢ÁŽì¤ëé|‹ôw»QÐßcâ¬íö)Z~럁žîO±É©ÇÔ_þŒ“ºoۍޛ™ŸnÓÐ-Aûz,ÿúäîßkŸð¾ü?­à¶À ÈÝÏÈL®?©Öԏ¸e ú*NüϪão¾ú®ùÎÛOœ„*%eäg¤pÑ`e/JØ°J¢o_'nMÏ®$ ÈþìZ¡¯¿p6ûç2·oÌDÏìú덯¾:túêyo¾øÎ$û杏· j(ÕàbIÄ©%
+‰}ˆîüP hÏwê
+䐪;‰Ÿ.ö°«LœúðyppŠq'Oõ¯·o|úä ¦îž1"’ñzPé0ّ4O±8ûñ
+KjÍ°Q!®ÚÔRd™"k’Ù°R†e#0DüÑ*æ«û J{ñ.‰ÒI
+@µ n˜H³8íÖ
+stream
+€ACQ ä\9ãQˆ¸f2 CQ¨À]…ÃañœV/
+/wkFFc6±TrÓ)ËS¢Ï¨xÄak§c1tA*È b×!ÈË3
+´º|v®£•Y,.Ûqºi­r}V°gªðöq0+s»µÄ7òÒâíú܍5¿¾Óˆ'ö¯Ó«×äŒ,rˆ|Qžöõ<_(¸ní8(‚¢¸söò0n‹ê8
+MRuGO<43Öí@pmYTó5RVT½[GOÕ-RÕuÕi^Um HUÜûWÓhuYÂ6%lPTM^'õe%ZÓäb¢òS…o7iüçT†2ÕÇOÊÓ½ÑuP–UAAÙ¡„uÞWmE{DwŇeށš,ß·ÿoÖØ kà
+W_ßÚÞF-á öOKzyîßb²’„à~—o¦N~C\àä²£ùæ{Y‡ ïøß
+÷›zú_Ñà·ÿ_½ó^vyòy~ÏèsÞë¯OÉD½Çâ֝ùy¼hJԓý5§Á=Ç£–bÛ>ÐÈ»õKšƒÐx®r–´û¿|0™ÚAw‹ZYJŸçíò@-m•þ=†›ѹxÇ
+yæ$h¡ò¥Óúˆ‘c!)ºxñ»R™ b Þãªu;1ÅÍÄ@Î`,…sÉJH¨ò¸c+Yƒ¤50ôR
+€2õ`ÁRZ¬éY¡-Á—žgóDUupíÆR·zJÝ=I84 x­yêæ꽫q¶ºõòëUû»y3–_Î4¿Z^ͯuÆ¿°9©3e‹Ù‡mÓ¾6¶ûÁ9o{/ÅüÎó·Ý;÷f¯fÛYfãÂå‚疐ŕ×Q㩃¬°–çÃeg¬53ðâ¶Þá{Úm1.*°8¦afó‹ÉÆ\)e<u¸x4¥ÛÀÇ!*™õÃ0–Dɹmñ<•\8ÓYAôåkƒÇªþYpUÓ[æM#ÉAŽþÐÜ?2ò¼ÏMö9…Í™Æóg›Â{3¶ÖÙÜæÝÃ>g«3æÞÂ9ÿîº7šw-*–ýlèœ!£«v Ëz»I»˜M¶t¦"Òz_¦i›Åm&Ùº$¢Î–ÒqÁG €Í÷ÓRTv»m=íæ¨å㋙Ý3Ý=îýEØw>ø\²¿6ǽçŸä °‡b¼oŸÅSþËâ»f€”]¨î÷YÜü ó×½Z9+;߈ð3¹xûá®o‚v¿±Óß°-¨1K;;‡JKä]Σ ·婍Žöìëø
+ßݐÖŽ&Z赛ä°ù¥Á}»Gס§ü¿© ¼GÎô’ŸíSM!=T—¯zĹBh×z?7x¶vìºþ®°›üµ»É}ÃÓÛoªj»E¿þûçÛ©I’ëOdEÉzÕš8#èÝC|=Žù£XÆ…¬hù)þúšŸïû‰ðÆð$`,i¤Šöiê" 8÷€÷O’÷§÷è²ø/“¯‰ëEïú´P(öO¥/¹0.Oö½ë¦þîøû°‡/
+ÒoÀþ­¾®ïËηïÒ/îòÀg
+O× + G2WÏâþÌ$ÿ0‚Ý0U$ÞݯoI¾¸Ð
+ÞPöCYP€öð!£|ÆJöf7ððTLÆöeÎáo/kÐF4€)>ò” pÒ¯"Á1Ž¤;â\,Šác)Êî鏍$€rÄ€ãb]Cè52íQN‚ñJFløè `x‰ RQP›)½q ï$4ÎßQz^ÉÍIÂ9õ鼦Ⲃpo=‘›.ñ‘¢VÐÀGqÃG‘à)±‚К‘?±=‘Bª‘IñŸ‘Q§1]kAQÒfiÛÊ$<ñü£E%Ñ}r L5 aÑê›1”²qí13QÅò)Ïb‰d&$ò°&[#KüwežŒè¨],A*Šhí$ PÉ&c#òNÿ)%DÉ$¸‘§ {âCBöXi`j1é'È\irlþ€fp‡,{â`žÏ#)#Ô¼FZ Œt1F‘_(òdtg]#âb›bötr±*l,(÷*RŒ³Rdu •+Ҝ€© ’É*¢‘.)H²AZŽÝ,g*2å(Ë/òÇ-1â: ±/±V`“
+kR©â0îQÒ@\èbp‡ï%r¿gŸ1§#1îñ3²ÐkS*;©ªcÓ3&³6ï­3ÒtÁÓO2R²¬®ðeJ'1Sk.Ç_4¤5Ó]$²@aÖoG4ŒË
+Ç*‰Èì*„~²»0Ӛ9ð$’W8âüu2K9‘lg“Ÿ4ƒg;h ;ÓS/¬)•9DÉ;Nñ<2s8
+ÓcÓ7ó«ãÓ;³>Áb×>³Û%sÞ5CÍ7R?8óÿ;–Át>ҙ?¯xjò£=ȵÇ93w@ÔAJh“?Èl'â7@4 †Ô-@«DÔL”0étl´9AÓ)@DmD¤‹=TS<ç_Dé¤-΋REÆÙD3ÓB”{?tL¦tŠC×<t[Cè¥GÔcB”—HPCH„PêáCÃéJt`QÔeK˜QÔN;¢µ*)5)”\N4º?”¶o´Î<”NšÂ›*ãJÃUMô³M N”ÖöìN;¤Ý,ó&?‚
+stream
+€AFaTb6‹†ƒÌf.Ãѐ€Z0 b§#,
+†‘hÄhAAAC˜ä\3’CÆÃaÆo‹ÈåñØÈb4Ÿ ç’YÜ6S,¡L(°a¤ÚWL¥Ð¨2ê”~f5„Áᳩàà\8†VãtJô ±Êg‘1½[k˜È*öA¢ÑP®[(ÓQtä\5•Ï†’»Uó3¤MépüE:y®Ñª°«ŽV.Ì` ÖÎO+³_ô8ût*%ÊÝ.ÕÌo:½ééÔ¬â§3Âa†‘ZNϬÈï$¼:u×{ŽßÑê×f¾¶é,\¸®¦Ówè[aî¤WeÏÌÈ2œ)%?WÑàÜFsÙÿ£kGÅkáÿ9×ې餯â´ð=*úÂÓ>nóüè¼k„<ïzÚÛ³z1#îÂÒ2†8°ZÚÈÁÌû^÷COü+)ÍRè»M0b†AP’Ãќ ŠDJ4(G(bEǨ49 äC*Êã$¹®»ÂÍ@| ëH°3K'¬«;¾Ú5‘Ĺ¹Òclϴ҂DœK)¢m"'prľ³3ð§Î3›-6³jºQ=K´b†ÏíD½6ÌSÊWÅðœ­?NIZDÅÍ¡šÌ©kó‰:ѬÒ}L¬ïk/Nª5ÊP(cAÎ!ÃÛL‚¬×Ôïì읰´%BúR•ºm6U¨ªý/¸îŠë9$•:Eb; /Pï¤Ù;26„£>TȅQ6ՉE£@Ԋýg][ñEbñ"vM´ÅC7<o_ÝV‡6Øõ¥´‘5L7g×A¬AN]Òlð”_Ö½©là·-;x$OXX®ÊmPa76#¢s†^]¸º ^êOCÎÖ8m{`¨HaŽÙ²3SH’V2 ó8æ3Þ
+¥ÎšUp=uŸ@x]W‰èjÍG£WÒ™W·
+ç åç’à•s¡NÔ²ÏHs¥§©29ºQ°àÛ%³´gùnPmš.€¦Û2n«âÛrŒÞÛEÙDj›:W«êV=)8ïÈVY)¯J¼iz½ WA•7±èÛ-ÕËm<ͳÎm¼fßÊÕ÷ÓYºG“A¼ôMm1ÒcœëÕXY' žÒæÿ’¤A—rö®êÍ»6—Lè²<¤ãâÖÛVxŒÛt…åú:—Qå%gYU<}©ÝêYg쯽¶ÃR*1×÷˜¡ÐÕZönŸ7ÿ1 y*¿é̾wôœ˜{Ç;/Mý½VŒõßûõgO„„½è
+øcT€®ó¶rI_[‘oD…<@Wà¾ÝI> Éû·§òCaY®y
+â›Í‡M~D×b¯œ\!ð­ DhËbK­‰q”9xžÀ¡¼us±V’—J·!Œzƒé„Œ'>ðc­<pò?Fwälb¤Š&H(âüK4L¯>?I5á4V0ñv-C7 Ðd…5äúS½³îxߜ£‡Íê AyG$ Ü”Œ²¶,ÉƒÈ ÊKöŽìÖ(ÆU-(j}˜Ð@%¹€Mæb·#Úc÷ƒ! БÐF4Í©pëctϚ²^ â| ¡$Ã(ä¢CXU:¦Tϝ‘UE¹Ý=%|ӌ³Îo½Â,gœ³‘RB~GÛ(,½œ²¬ŒÄäù;(aG™
+ªx“ê%* ΢Ñbub1hiNšñŽ&Q*÷$…2KÒ]LúUBc^9DøGj §m5¢gފӈþô¨Õ>ŸnÓ©û+ÈLL§TžWÉ
+Jè<e©ôÀøc”úäâÔ%’¬F¹à€*ìätïN°ÕCÄF=a¤pþ¤Ú±S T¬&ò¨ƒ:Ë:©‘K#DúO
+6u…›pþ¹Xç}KŒ±L¸ÂØҚ’Û%®Åȧ9Fwg¡œêU„`¦Ù²gGŒ=z´“ZDÏék„D©®ÎÜT5Kmí®&…šËÚ3+hÌ°yZ{—G&iÛ#2³X»cs鵩ÜÝWen¤êœ7Nè<+;`dç¦ë´ØÙ(P­í·Ôféª~øma¯¾VÑDš¯}¬œ´²§V±[û3€.^%֌ù܇ñr°e¥·VÀ +ªhìF£·ç
+Y‹e‰o6 %³
+õÕÄ?„–ÅñÅ÷
+¸CvÓÁ;¿çös²ön·hšÇKlª­è³VÝÆï][b]¹§K²Ô›Î
+I2Ÿ¾6(3ܙ­»èóºu[qݛI_覙¼xKxÛ:ïˆèQ økå5NDqÆD7‘…;¼ƒWg÷WÂË&ҐþsðGW] f«wLÏ!o¾EÆ´Žä<ž¼lpoÈ^+ÃÞ´ðéç÷µÊ:Ô庭íq9ýÓ*̏ãC~˝þMº?=ä‰u’JI:—Dö›)õȍ4·bé[;µk•²û]È: Rv®«84GmÕ'c’¢újmÍ7dýþ÷ÙÙ|ÅΞ';˜¯ ÷§oÙ'¹ñ~ë;¼Eï>½ìbRàÞ«Xç®GÉ =fíKÐö¿S9ƒLî)ù[wå⟙>úŸÖñþý×#׶9ûÂIoO=L–é•ËIX°¤É$@ס×ôyÆáûfxI7˜Ê§Ä뒷Ãú½â»L·ó»Wƒþ§õnÿה~èÖ{ÏՖxíë“ðĪÄNü¯ð‰ÆùoöÚXóðHNh›OèçPà-Žû®¸ 0¢„ÿê
+ËM$çІ­-ÎÖܱ4ˆmõ‹̌ßñ:ó¯óŽúð%©1µ©Š¹Ñ[M£‹fýqAËßÑ$)±D-O0(0±»°2§‘Y°ŒH‘aÐÚQ˜Îñ@¹‘ròÑ¢pp\êÑ7N?‹Ó
+stream
+€AFaTb3‹†#aÊ3 EÃA €Z0… „#,
+Sñ”½.’BðÀe´¼TR¬£?énÆf$@“SË(‹1¥äÍh²î ÊÂHF"‚¦˜S].Æ9«/HiTJ,©q8cd“~X‘…Å:ž’œàÊÀG#*§¡
+tÀâR©Ò"MƜ«¢·g @Ùq,$ÑÁ‘‰7)¨Q4t¤aöÅò{BÞUž1dÐщ%;¨z‘taõÀYû)4™‹¸H`mP)ôçÄò*)štØS‚ÌØIÂg§Ì©*­Å%P͂F§m6žª¢YRçåM,Ñ<Æ/z¤ÊœåK!•!: v!Wa\(• »B5Y Å<¨`Ø¡¾Ú¡MÊmm1‰þµ¯òq]
+l$‹¾[VºôCI¢ü­pÚ±Êüq*ò°ëò·ÕuN«QÓ]î¹¾z†üªas/6\´$f͝'
+¢ÐkC Œ²÷áaXë'soõ:¯ÙW;S`ä7žõ®Y™â$Ok\….Ø.¸·WkUå¥Ùt –wam©¥<˜ƒ ,ë~îFz•¶ß±†Á~šÅ«¹Jøã2ÌÉÉ£
+¬ôUvXpå`|øo
+c{hN'&>ˆu—dl. åž!«Ö±],bk2­×ªh~±bØ~jýN©Rw-TCc–qòÔÆÙNfß,·3qf>]ïÌ_VUœðH!.bÜ÷˜09f¹•ß@²­Rð‚¥Õ¥šÝÌGi‘ËdU):¬yUÁžªALƒ—šÜhŽ†–9= À5?vâƒprȃ‘á$6² ˆÈQ A* ^è
+˜ƒc݌Dqéƒï$…M#±ñèr úì,^™ áÌP°@‰X0 ˆ*2FƒÅ
+Ü°PCÀc ¡°6PÜR !¸3‚ZAÁ@e!t*­ÎE¢º
+ƒî]Ï>·^í½ðPC oL1ï°Üwç༶Ò+Âø|
+Ý[°€ˆCl'{†Päƒò`¤*®I×ç([ r¾$ƒ`aa ÐÊCxrßÄèžEÁºäÛ †t3ˆz0
+ÝÁH:ïÞ¨Ã(d2‡0ÒÃwW䆮[t-Ð Çå¡ 7†Þ¡Üyï$šeS»l-Íظ˜)ࣩu@Æ
+¤:PÆ©î]dÁæзãðۀ«@Ž#â )Q@ ;‚™d
+­öÞ@A
+ƒ;
+àê àñ
+‘`§°VöàçÐxQ~#–ï±õ
+Ò:> Q/é!€ênÏ6Ç°k NºîòЮ(.. îÐ ïï‚/i*C*ðÏñ
+Îw;ï¾"/ÃϐǤŒ8PᱶÜRl SP>B%³Lې"Jª
+Ñ ±Ý Ñ(²¢æ3q1²i$´°ÝÑÑ
+ñ×°”nbþ’«*ñS@m/qQj÷¯/\n« Øqù1t¯N­ÓNï` ЩXåò,æ‘Ù)nrþ€[pù±¥A4Pþ“3
+±•öíÇ!s Sϟ@%(n=1.0ï Âû.;ñ¥M°ò”Âۑ×
+p«U­¸ €QrvéSpÝÔ¤ï¢[#ñ  à§!n5O”õ#ÓQ ñ•4ò?)-é2² €Sî@ú²äpaX¼ÜsÖÝÕ ÀëLVæ1PR’mð µI
+µé¾ÞÎÛ°ÏBî°4-Ž4$ŒÀntM„Ò „Ú­®
+fDÛmºÛà 3ÝT@§#àÝ4àäí@¡î£ù)ŽJñpµLé–gpPßÏ÷ajvx¬zô]$Ö]XN[R¬öî9X®¥ÉF7ev”Qkîë“u TJ
+oìÿõ;Ϻ¥mH n¡Â*aªad-¨ÚÍ°ÛM¸ÛÔyGåJ¶4Ԋ: ±n0&/0/dvídÀAeõ_ä p=Ž6æÀÓLR`­zë-Ž
+@Žàà”Ô€ÔtÄà@ P
+(–ÞG*Ò0
+–`Au,›töâ{çÃu€kn_v‹Ž M9sD:dMÐÊ6Ú`Ãlæ>ÍT‘wXï´(6æ§Ì ¡Âïy7wx°˜wœ‹W 'WšùjtÂÈâ‚-
+| yzkùʘ!i°ªL ¼Â#QéÁ{cÈ!bP¼­‚>eu€Ê¢!cv·L¡€xº8)ƒøBÈ·ôq¸ F!wímé‘~§Z/ó|'ÎÊg{f^\hªËL šÅÆËø7Ä©8yy‡ Ì׫xɐÌ؊·8~µ7L7‡ÂÌ×éŠ*ۉíx£rQŒ§}ø¢½Æ”L˜Üp(eBŸƒ8¢¶æU†XƤÇw
+|@r¡”?…J¥ŽJUCóÈËXå€K‹8û‹–<½˜âhe%‚÷¾Xåt>x¹ ‘˜‰¹
+]åt!x}’y91€—´Óøæ(‚ƒ€ C ÁŒ/zÍ}·ñŒxÔ³«‹I`"7݈¥ØAy ‹ø§{×ˋHcy
+• ‡{8’{9_‰Fw{#B§ÂâÙFk†ÂïuN&‡¹FDÚY<«¸l7W›¥M‘ ëŽI`>Ù·Y͊y‹ÙÕøÿ‚˜äœDVf™žÓàq‚&iz£ùxKŸL£¹íCY<bYŽ pÃÙєfÅ~Ù†ùðIøƒ¸ï¡©m‘ -¢9~y塨!yÁ¢·ãD¤y£Y*_ l?˜0.è_¡šG‡:¦)¦yǁØ‘Z/9-…ú5†³­”ú4ÂøÈúhŠ˜3­£¬ö7«îȹú¡Z¢ª:Îye€¹ñŸÂ‚¢Z*Ç:¡«Ù
+ºš²©™
+stream
+€AFaTf1‹†ÃAÄn0 †B˜€[ÄÎFX 0 ‡Øx¸b Ddqy4j9‚‚†cÌFŒ"‘´Z1.ŽÌ`ð‘¬Nq&ŠKgÔ¨Ý?!HÆ#i¨æG)Jçâ
+lÂ?5ÏjuY@q –Fk’øôÊ.¢Ãj‚ê´R—j®Ûfr¤Þæ8žÊm»Í
+h.T¯óÛ6™l¡[î69ö+i W¦RÊj7†Jn9‹];75±\ô©:ñƒd¨Ú¨f_ °ÍÈF­DOEÒakâá¾Ï{¬âÝó7«}ûŽ3¥pw>„ó=p”BµÜ¼4ÖÏ×ò8}5à¤Úº^Q‡C¿”Õû\­.jgUÔØ,°¯§
+܄¹Ásâ»=o³Úâ8ȋâ'°+˜ˆ7n¸dÆ1
+òE 5ðÂ!Ç-cÃ|S ºTZÃ:
+ä.ŽÈq;Œ'Ê(„YÅÉT°À’Z>èKô ¤m´¸ÈÊêœÎýËqëì·ªrÄÐô¼s\ƛK´)ȓœÚ¨¡P¤ã*¿é3S(OÓŽ@ëTܸ6´|Ù6r€j†"È¡3­'MÑÔüÇ,ˆœÕ9AôÅP‰ËT³cPÑlEUY3iMI¢²LóVRá3EuÃ̐Kìi`#éHoZ†3M—D 腅,Z*K¿SW1%&C’Tô·S³0]p).M¸™¥(Z䮑Åf\ŒBýx1Õ1[¬˜mxTùuÄ÷µÞ‘`T;ëH7ø8oRߖ® ©Þ|AcG/>(¸ZS-‚¯¸8kiaOõٍ_ìEÃ_ڙï•)9+§ŒÆHgãØ%˃æêM=ˆæŒUà‰)9Î#—`ú#¡ŸÜy=E”¤ó#·…Òù7¨Æ÷^3§†Ë¦;©äÚB§®®º\©ªY·:ý®°
+dsŠÎžAgʾ¤2‘9½H€ccñ
+`Km I4@À£¤#ŽÇ¾J9¤Æ$ó•„MÚLH—A)ÚÔ©•ò†VFië#„–ÒR\Eøë+d¢2‰œïä“ XÄÀ:(·i‹&^4´fs”½#ù,eÜÕb2l½çã6ISYÏ~@Í×É5åÔáq
+KMÉHh‘›‘’Gòq? &ìt3`Ԙ(Õ”„ԁ­f]OÚåü݂ôb#yëBÝ4øë8¨êMRõ„4")>2äJWBxG²`8DgE¥1TšvÀ¨J׉¬““¸¿9ÖDhº54ÙÈ1ú^\©á™³N]–-N¥EH*už°JRáåB’&F”IÉ.’uP‰rúŽÔ mUɎõ*ÕɜŸ*€4C”â®Õš¾Ì*•b:ÕB/QÊÎÇ«£{žFEå׊ÞÏdÄå®u¾2×ffMT•„x4ú´XªÃ`©Üo¬Ö¥U±[ ˱*†™P
+õ½u›r{ZµmÍâóöÛë|¥
+6:_M/œ£xbf‚ôK§Ó]_§t3Öۜdæxã1^B¢ªO`pÓän­s:IçkÂéK€®µþßN¤žþ™*¬Ã3ƒ¾Wç\ûü³à'R´wûõû*
+í†?l; È %q
+ðééÙfâv„(½Ã§Qw†[§á%I‘†BÄ(Œ½
+àÜÌ$Ë#å,R,ÀP 2J ²5'’|Lõ(RˆBXŒ"N
+stream
+ÿØÿîAdobed€ÿۄ  
+
+ #"""#'''''''''' 
+!! !!''''''''''ÿÀ  "ÿÄ¢
+ 
+ s!1AQa"q2‘¡±B#ÁRÑá3bð$r‚ñ%C4S’¢²csÂ5D'“£³6TdtÃÒâ&ƒ
+„”EF¤´VÓU(òãóÄÔäôeu…•¥µÅÕåõfv†–¦¶ÆÖæö7GWgw‡—§·Ç×ç÷8HXhxˆ˜¨¸ÈØèø)9IYiy‰™©¹ÉÙéù*:JZjzŠšªºÊÚêúm!1AQa"q‘2¡±ðÁÑá#BRbrñ3$4C‚’S%¢c²ÂsÒ5âDƒT“
+&6E'dtU7ò£³Ã()Óã󄔤´ÄÔäôeu…•¥µÅÕåõFVfv†–¦¶ÆÖæöGWgw‡—§·Ç×ç÷8HXhxˆ˜¨¸ÈØèø9IYiy‰™©¹ÉÙéù*:JZjzŠšªºÊÚêúÿÝÿÚ ?ïù³fÅ]›6lUÙ³fÅ]›6lUÙ³fÅ]›6lUÙ³fÅ]›
+ôSärC <öbq‘Ëw¨æÀZ~©cª@.lgIâ?´§¡ðaÔcƒ+\›óf͊»6lØ«³f͊¿ÿÐïù³fÅ]›6lUÙ³fÅ]›6lUÙ³fÅ]›6Õ5;m*Ù®.´qŽ¬ÞøœUVòöÚ¸ºGØW©?Ê£©9ÖüÙs}ÊZÛÛnŒÃü¶_øˆúI­SXºÕî Ó5m²«à¿ÇǨT¦O-›£7;”Šÿ̶6ޘˆúå«C_N0•£°¥w¥Þêڎ ±^h7*脙,¨@|LTsgú:)ÃýGA¶½å,Ac·nJ7ÿŒ‰ãþPß"ƒC½ŽùmÖxìd4~ªrRM`u¥HP
+xÒÛÏ¡m” Ä;¿ˆ~¶C¢yž×PXRek[‰€1Ç( êV¿Ý-I`)×$ÈÊßkcødRx¡LVXâÔcWP!øìܦ»îFÿ14­K]ÒîÒÛ]å-´«H^4yÜÛ—*íÝBü–›áE‰q-ò¸b6÷qIÉb‘e±G
+A*êšt#ÃŽ,*»Œ(Rà2¸bÅsqÅ*<2ŠbôÌWAÍoñ˜æ@èz†Â;ÍX«%e¼GíõOídœ ðƔ)X~Ÿ©ßéWY°™ •v`:~Ë©ëò9Ò¼½ù‡i{Â×VÒäì%ÿu9ùŸ±ôí‘{í*ÞøraéÌÃ2õÿd?hdjîÊæÅÂÎh“.èÞÞÇØ⠋_B¤ªàjàŒS8——üç©h|`“ý&Ìz,wQÿ·o—Lê:'™´½n0læ¨xá‘Ø÷ùŒ¶3ªQ!<͔¼“f͛ÿÑïù³fÅ]›6lUÙ³fÅ]›6lUÙ³e$ìSŠ¨^ÞAam%ÕÃqŽ1SâOeç9V³¬O¬]´òšF6E_þ{ᇛ<ÀuYŽ³¡DHB?l‹ý=½¾y„ pÐH
+ z@¤žÙTæ9tonjóÍ_Á0LTbJ{ãÃW"•Q‰ÜÚÛÞDa¹ŒH‡z ø©ê#}k5ݹŠ †¶”K"xŽÍíŒÒ¤ÔÊÉ¥WŠgR) ñ¦;j `÷¥wViìe‘Må¨é!¯©¼¡7u#|¸5&cL2)
+‘Ö„ÑPÇNßÊ6÷É ìN6ÛJ··w–(ÄM)äô­+â ¯zd<2¤Ó‘ã DŒ‘³ö~Æ3e ÝÛ_ÇwbâÚÙþ6Wåê*Óh
+QÔЂ;‚0˜5d}]ÝVëÈû³±î\ڕz`¤[Þ|¡æGÖ4à÷$˜[Ӕ¹l
+µ=ÁûòT’†Ã<«4&³ 0¿¯:¾¨‰@ß/!mæiæÄ¢~C‡ÿÒïù³fÅ]›6lUÙ³fÅ]›6lUØGæëÏ©yzõÆòHžŒKZU¤øi_
+õ6ºžÆQGþŽ>ÔÛü\ºa´$¨3Pzøc—-ººG%ð=F%gg¸"!öYÎäý8 ù3”£(ò©yr(•$š`•@7sOl
+÷1[©ß~ç
+o5Àµ²vÖÈîFÔ_q¬¢Ö‡"—¼’ÄฑÏÄØÙ4úïZ7݀$֝ºa(5êröÅšNfï•õُí-FíŠ-.e=Xã…Äž80ñdž¥&rzâ‚F=ð(qŠ¢•s® ª_5­…ÄÀÑøñ‹ývøŸIÁJǦŸëw—WuªË)XÏùþí~úWZƒŠ‘Æ‘ŽŠû²äz 4„ÿA¾6ǀ?i¹Õü3©ù{P.|âÚ[7¨>yÔ¼°[àˆšŽåêö2ò@p}p«M¯¦0Ó
+ÿÓïù³fÅ]›6lUÙ³fÅ]›6lUØúxí­ä¸•¸Ç—vð
+<]ÉÝי`œ—1|®7ñHjfCþÈ\.â}Ê@ß8£?ñ®<Kÿkcÿ<"ÿšq¤Z(\Ä݋ÿ1Ââ/÷âÿÁ $ƒþYm¿äDóN8Kÿkaÿ<"ÿšqTGÖbîÅÿ‚_\ƒ¼È?Ù뉉Ôt‚Ü| ‹þiǭۏ²±¯ú± ýKŠÛbú×ýþŸðCKÈXŽ,[ýUfýC)oî‡Ù•—ý]¿V_×®ÛíO!ÿdqM¢UæmÒÞv"þ bƒëg¥³¯üdhÓþ&ãúîßi‰ùœÞ²¬ӂ•0ÿI=D1ÿ­//ù4¯—I?jæ5öŽ6ÅÙ?V›Ø|R(úq#¬Ù¯Gæ|W+a8?ښgùŒ}ÁXþ9ׅ¡¼¶Ž(©2,’vj…GÆÄoBzf›ÌEaœöúÎI5ýÌòÜKÆ7”‚@ހ
+*É”y§3+ž*j{Ó rƲ3?±Ø}ÃAàAà2b=ìLû“"Ò.u,[lçz¡.»g\òå¯]²Lžž”A†Àö©ÅF
+Š:
+á< e¼‘û—ÛåZÃALùÜv”þà÷?ïÓ÷bÑ@_¶E¦»Ž™*Ìl÷¥\îߍ—Êãýøß~.!ýœxÑdþ\hw-žö?ûÓÕÛïÊôØõ©ù“’EÑ$?³Š®„çöpÐE–/õzþÏáŽíá’ÔÐþΏˮgaËjç¶,¶.{dâ-±ýŒ0‡Ë'ù1WŸÅ¦;vÃk-هÓ»,tø0òËËaHøqV?¡hÌ¥I\éZEŸ¦«¶'a£¬TøpþÞÜ ˜ª"%⸦PËÅ_ÿÕïù³fÅ]›6lUÙ³fÅ]”̨¥Ø…Ubvùyó®©õ=7êQµ&½ªuïÓP¿N$ÐHi€y—Y{ë˝EAnDEiî+Æ%ö©<Ó… ¢ÒÕ`åɀ«¿ó1ø™¾–$ã‰ޓþê³A™Æÿðá°üõ')=í܅%×RԜ,•«‚fj“s
+±abž«ÏË+ü˜ºyi“'ÂÍ<1ÂÑlUƒ'–Óù0L~^Aû92Ê;c„
+;b¬Z=ìàÈôhÇìáø‰F;‚ŽØªQ—þÎ
+ŽÉ¶ ËÅT’\P2ób®Í›6*ÿÿÖïù³fÅ]›6lUÙ³fÅ]œ‡ÍzÏ×o®o—ãŠ?ÜÚ'óx 빯ӝ͚Ÿèý&D©=×îc§PøÛè_Ç9+^ñTÿuh·¼¬(ƒýŠïôŒ„ÏFÌcª‘_ªZ¬Lܤ5i_ù'o¥Ž]KRNjԟà fzålŠCˆ‘Š1ßpª™Æ‘ŠiñÅTa\+¼œ±ôÿ¬GêÁw×’Ð}¦û#øálh]¼I뒌z°‘è¾K)’m#M22š`M/O20Û:6£}’W,`˜ùHãÄñ·§ZˆÐm€´½9cQ¶H"Œ(ª¢­;6lUÙ³fÅ]›6lUÙ³fÅ]›6lUÙ³fÅ]›6lUÿ×ïù³fÅ]›6lUÙ³a^¿©~‹Ó&M&oÝÃþ»wÿb7ÅXœõ”¸¿šJÖÚÉLq¿&jžìÛ£"à5­­$?¿”™&#ùÛsOaÐ{ Vô‹Äƒý×'›À¶þ’ýà·Ð0£qR@9I6m¼l)-º—“…îÕÅfzœNø°åW,åaV± åXг×v Â[ÙÌÒzKöTïîpeÐPwiä.ß@ðg§Ùm¬íŒŒ6Éƅ¤—+ðå­IŽ£ò*JçLÑôÁ®ØC҂*ž92µ·£lURB¶ Ê™x«³f͊»6lØ«³f͊»6lØ«³f͊»6lØ«³f͊¿ÿÐïù³fÅ]›6lUÙÎ|í«¤·o/ôkndw~¯÷SŽMµ½Et½:[ªþóìBwnŸw\ã×ln®ã¶cÉT‹›’w­îÔÿ¬ã—û„ÎÔÏÞÔW•½©y….'&Y½™º/û~Œ »›“†ºÍIíÓ#ÓÉSL­°©9ß®Y5Ɯ(q8ÒsNG
+$(RW |½¤ý’W:V—b#EÛ
+°É4‰+öp÷KÑ°ªáMªhzQf_‡:Žƒ¦zj»av‡¢…
+JäîÂÌF£lUkcUxŒv*ìÙ³b®Í›6*ìÙ³b®Í›6*ìÙ³b®Í›6*ìÙ³b®Í›6*ìÙ³b®Í›6*ÿÿÖïùüÍóD^_Ð%€IÂâõZ2êÔh⠇“m÷û#ïí“9¥X#i_¢öO¶yÛó*ãPÔ5)fwôç
+¬£Òt¦ÑÔö[2ˆßw˜êwm-Á–zG+Ý]Eº:õþÝò´­&ãV¼ñ*ö®'AEU´kOÕ¾-§i7÷÷ë§éв\KRб
+/y £qQ_é=2ÏËÖRµ£JÔk™ûÈôëìa‚!$¤×1CmYÛ
+‚ÄØok\~*ìÙ³b®Í›6*ìÙ³b®Í›6*ìÙ³b®Í›6*ìÙ³b®Í›6*ìÙ³b®Í›6*ìÙ³b¯ÿ×ïSÆ$Œ©ÜÙÏ|ÏåQ¨V‘[—OPlŸåW:1èpªü|&˜«Ì"дÿ,Y½½’òšMî.X|nßÁGa‘=CœÒœèZÍ»È[lŽ&ÒIR¸ªS¥im#‚W:>‡¥
+xà}F ĕɥ• Fت½­¸E˜4
+°É(Ë
+;vlÙ±Wf͛vlÙ±Wf͛vlÙ±Wf͛vlÙ±Wf͛vlÙ±Wf͛vlÙ±Wf͛vlÙ±Wf͛ÿÙ
+stream
+¥vt9¿R?Î|­
+¬ý•Þë÷‘UÔlñß,؏P_¬”Ô¾"²&Ÿç‘â+Ç£g¥.0 a9¡; cG˜¢À/ÌX*ÁxÄ|™dYS:â
+Àëœ9¥²aÀH6dܚ!n:`Âïù›vÌ=„¸ã!V¹ÐwÆí .g„û-BˆÔ„åè+‡¯´zmàfAAïu\À‚
+~µÿ~…ןôÿã«¿
+ð/)Àï ¦AÆ`ÇOAè
+Æ@+¸@R*aÚ1Y1p<²ÀJ(Ôöabœó«.PÚÊÉUE
+ٓ%v+{FOö4{]. îƒW2å1ºDÅö dÃ.ìÜû4hÈÖêÉV+ˆC¶dO¶XA²ÐÙlqÈÂýöì]x{Ã^{bÃlÏBl|cÃtXè˜Û<²`~Ò3{Ìæê±){lŒödÇã°Ý1ªc§pØêÕáÀ;dÚU‘ŒhS|ž"C¶I¨`O«Ú„mx장H:"iN³%퓧¢À:²öÉSY`Ïçͯ²öÉSY`Yûä©,°'.4°éÑ ÞĘ[‚÷@«h҈]ÀžÕºDô4ƒÄ¢ÏóN”HÃÏÆd·º4H²Þí]I´Y’‘․éi"Éb]g Š‘'6<g=º×ÍÖu²¹ ž“ ÀÒtô¸ÙUXS¶Í@E¡èýc ûbïB´Í˜cÁ¾U¬QƒYè[å1ÃÐX $´­òœ;ÎRÀV‰ÍaÈbOڍô&sJ§w
+°ÑkéQlÈOgù ñë7X– €úœˆ^rˆOýéɂÕúæypA‘Ÿ7˜]¼I?0ÂÇÒ#j>c¥:׎—Ê€øøHò-¯ 2hÎÛ] ¤Œtz¢Ö2L)Ë?;>ç€*o÷'„žŸ—ÅØÇëæe_€b¾âÅb,å~§®}Ç,⏖œ".¢:c´ÂN• ®kÙ0„:I¤V’LÒ
+X”­Ë.š­öÌÅ"Jà4—2v‡ifl|‡¥sJF{—x-ð\n†ÓÈ¥¨Zã¥P[8VCƒ*^1Ô؝dçI8N2\ïz4PÐ¥XyoT7aGguí¸#iWâMæAPó4p–{”{¼Ô’.ýXJsÀ<9׊òrÈ©°ÊÝR–· ¾\ÖC¬kkž BmÖàtQ¡ Ë(þÖ
+óBÅY櫯|õ•¯¾òÕWþ—}ƕÚeêƒ"ýT˜šŽ¯
+ªé¬›)ƒ7Xå¤ÔB‡á
+rª…±#XÃAíÂ&ÔbïšÜÔZì܆g_w¶ûF7ñ û"ó
+nQX¬l
+vWùBn°a!yOrĦM ˆ}\÷èì{ž-ý雖6Øm҅ݺk²ê®MöAnK_Dáò=mÚzÛ6]m°Ž·Íik¼-{Yu·9]MDûå÷)±æS…Ùºélìnu:›°[wMv¸k³ân5û“ºK¢[wuÜ-¶·™9Ç×â¹j‘!Š¹HÆüp4vµgëhñü,ž›iÓ ²Ž£ÉmP&;\µYõ5¹Ê´ê?|—ݵä „#Øn}Ì?Ǧ1›ÿë
+ÀmWéeÎÕ|]¶
+ƒ$¶[¡Ðî¥ÚH*”AÇnt ¤Û.¦}¥¡kiŸª©ã6
+eð½i¶Ûà(HÅm«œšÛàV¨†Áí65Ý^¤@Í2r¹êr ¤Û.¦feuì^ູí^°@]ڜä_îv@jvBâài0ØuýgBä»Ne~NÓ耎ÏF*T1Jwñ¢Ô*¤Û+¦feuÜBí¶Û`‰2¿uTf·VÏnuJ¡!môj=ížý²ð±Ûk…êúhF…Ô§ùàâLP‹R¯N¯™W”Òñ
+š§QðQiRÇ,”n·”¦i÷"ÓS«‹:v/·6Aºíbڜ¬Žß ÜáŽß‹”'yrü~¾îb±;!³kÛetÚ¥´Ý“ÂvM‹íN
+í¥=þi{Î:/BŒý/JÍQçEÈ´ÔQ'Eh:j:†aCÍóƒà¶aÛïtÌ4ÏKó¬”îy)¼˜0ҝ‚b²ßëøQ-5TH5ɪÍõO/|ØQæõ‚ÑíSs”ßÖ1”y¹˜Ô1”²bÇ'¹Ò0®ÁÚou>PrëA"õ`>9FÇOtˤæÃvÞêø‰n5ˆ¤$M9ˆçI…ŽCº)Á×±w:f‚ç%p+ýóí܋Rj†Ðå†ÑvÞKý,-1¤ÔqÔÇ©¼ž´hKTÊîF©_Hƒön£ä󭬘ÝîÔ
+¥Ð®>·¡ÉÂÌ6~ñ1JÍBºÍ6RINNôÛ6§(åfkğ6ÕEG]Àf«SeÝf+¹ùœœ¨ÙêT¥Ülñ¼ïÃÏ*‚âô»›GñÄ^Šg¥`'—¾3u¸I§•Ô=/É­@n7B;É­1‰Ô˜i(¾Oó1ÝÝiÈ絙‘è‘HŠÈ|pÈx³e£Ž¡à–H·!¡ÜPp E@…¢ק¿"ü@3§+z~.·R@òǤù¹ŒÇÏåւ Ղå§}¾ÔÎ`ÔÍ„Ä †ÓËdß
+­v¹¥ÒmèBmèrKÁEJüwý|q%+¤~%~?õÐWÆӣӏRî§ã¡ çé†[”útûéð´›LÍO'µ@asì4ïë4Ï ‚âe±W6ÇIóŒåð1_Yp%˜NŠ3,J½@jf
+8ÌÇMq
+%\ ¾uAÇPr+¤ÛPʞ¡äV‚äU‚ÿ®çt›¿RP㢡¿³*Ÿ+/_4^ë´Çqxnªú‰„픂—Qp
+’Ïs‘,À³y£•Œ|ØγQÊÓQÌòQH‚lgÔ«dôØd'#¡8£`â8þÄ) ¥)fý^a–œÚóXXNB½œZörJsìäTÇÎf®²ûÂq|CœR¥²“Rq2*nBBG%ÀùžÎlRwÒIlgg£¯WZ:ÉÙ؀ÙE¬Žý*ë•qt’ʤ!cé4FÑ.•h¯èi¯ÈµREú8EZ ãŽúTŽ^‘?m¬þ³foiëoí¡µb:2ÎóÚJ©Þ)}ß©ÖÈó’„
+ÃQ:Ò—(Í$©IA'·Ê´ñ!é¤ÁÙª£öN;ÌÉhƒ ¥SZԚEaqXz•6“Çy®€rÒ@÷­8Ï¡mÿÎ)çñþ6Š÷·Ñü¾Ú (¿˜°rB¼ÁóG!Þà
+e‰ï¡|@ eÅFØ?õ'Jʗøgãú ë( çÇu,Ô õÆ1³˜a‹?a¯½ý-¥¥®P~s Çß%ž¿ãL<$N8Zþ‰,ú3²ç‡¾ž³Â6ÖCŒçü~§tô’óÛªËó÷kt~†m| ¯ïG£¤ðªÃá3Ôçý³ Ø#ãŠz½Š¦øž÷¤ÑÏ“/uû÷“õøíÉùûýô[4¿oŸëŸ¿I·•…û2ªîŒUk÷ ¿a4èµÄã¹ñ7œ×õÖ}í»‡eÙ qÝj~B[™ùáùzúãÚ Óç>˜5vý9_7¢k9n}uó^Ÿº¢ï}ÊI¾mì _æ7Üٝ+ê=4góÈ<Ãús4aÒ±ÑÊoþÙíDŽÌµžßÃûRX»j‡öÛo6ëç7Êùvlë0ò÷¿ñÚkfùù‰ŽIÞ#[ž~ÿ¶_‰÷ûþ˜áù ·2:wi—5þŽÿ§û}PÝ s#Ž%Wúøñ¿ÿü÷?U›Y«y´Ì2~z¯Ø‡JË,Cƒ©´Ìúìl‡JËthøkÌÒè˜JÃlã b*Ó¡Ò2ÛóBthùkÆÒHéËrŠÕ£Ò2ûؘJˤT&cØMó ‡2rX²eŒOXÇñڐl™šeúKD%C$Ýae¹ÊˆÉ¥
+Ñа!íýÂxÈ{¸@Þ§ò^,6ܒ¦*7N¼9
+(ëN‰G E©W‹uã|Ks§ÔÆ4½²N/¤ľ¢¹1v»‘¢™3ۍ«%ڕ”Áz'E°íKiƒÙ|ÞJß³y·;é{¨Ÿ—y)·½e譔]AþÏwµdَ°­Ô
+œRlRDJäU
+p²[odé!áð4,DeœDg!§’ƶq‡RÉ«,Òö(ÔØ6îÚnàAð0lFd8]õT¢Y8„xù©Dƒ²¥Ô‡7M;Š°Éó<Ûæ¤{µrÏ°þᅥ5ãŠû䯂i0ì8çŸ_EÐW2°vÜ~„qð·ækð­£zW$Ï6ˆ—G]F°tƒEGóǼ‰ÓäŽ5z(sýPéLú$!+‚™Qño^`ùIMxF1~ ]*4 |©º&ªË³}Ÿ¥€‡å½zN'°TãZ!;–ÍÑ
+;qøT ®-|¾ó[Áÿ¨¨ÝÃLûþßÄZ•¯^ª–²|ù|²î©Ë߅Ï_+´ôß@؏çý§!gÜL+蕻<HU¾àw|¶¼èÄ!¯ }åPêñ·ÇËurâ¼nÍù-cgÇ*«vž eÇú¼çBÓßS\Çó}µù‘☘‹Ã¹.ì‡ÏÛß°óóq´õÕúÅy)ž±þ9þÞ1 J^vyÅßqɇ8qþ­¯k0xˆ¥zòø<¦µé ¥bRïéJß$¾õ`KÁD¾•+„»,˜æ+Ãëä—ç©É¬•/ïÓÎõcL]}XFèؚ9rò6‚òï3Ê6%¤üøº÷3µÃ,Ü!ÖB#˜ O§ZΙÖ`§Qö2dv<ªþs-NœF¥åBS<Žæ3eD’ÅÌ¡ïBŸ
+ê>È»¬Û(Ïïx ,1r@q4Mâ÷#g®ï‡Ü~äKÚ:6”}{wVÓfIèqq§ÕNÒ×אָb'c’_ÖSšd;™ú“;]‡›Lçª=ESv“¨vZö¸M’Ô?p§ãp“¹ï΅m“Ò~˜Évïœ?퇗ÌÇn²M*Å/›ä‹1ë¹d»Ï ç¢H+ä!u¿7Ošwmær¾Ñª¦ùtWcÚõ¢Q Ô%Oú*¦ávŠ‰¾Š UŠHUÒX<¥µÞYÕB×Ë䎊éÅS“T¸ËK/v[”oRV#~,¨ð½°®¿Úôý‡ M›‰Ÿb²0W148SÐf¨ڟ)öh?T ÍÑ»¿ÒÇd)XtiÝFZí7ȅn#Í¢Scoë¦x`Ñm¦Y´‹&ýxƒîñÀb‹µ²K<˜44G“†æhÒÈMöÒçÂ>¨€…M·vÍ3ÜƎ“½õ•Ð¸¯î”
+Xçðþ¼yFÛ"ôå2“€ÄyÉ/Dž£êÑ=›‡ïôª³GW¸ª;Œ%Ÿ|š°A’]¹²dWüÈ=ÐÍDÍ=Ð
+‘³í¹ç´:¯¡ú7¡s·wûyºmF¶’#ð•á7e‰L~$žØÕî•%7PW¾‘­t‹ /23éYRFËK),‘ƒ@»Ðøo½ß¾ÓGÿ²
+ð«?¥þdÜ~ÚqÑ©˜aâ"ÿÂÖ§W¼¦º~Øù‹#›ü'®øùÕåÛNÈQ©ïJ7Ú~OU /áÝñØ\Úü:’J'×ج!(ÜG:KfÒ!"ºüêŒ@ûk ǔž€Òqg÷ëxI@{ˆ™4E @?ÎޜtF­;iúegÚÇB£kœh*“¦¡r§º¨¯¸Nú8É<Šýmì¾)"h—´¿×ñÐÁ¬J3¸<§4£kCµÐ¤ôº»& •B£R”TŠÌ*AüQ¡CC•È©†•"Ë$ÒKø)Ž?J¢„£d¹Ÿ›„”£•ŽÈ,ŒZ£ q^÷<~%JÐLÝÇJÉ%ÀhàyÅQ"ÛÁC‡“čêSŽ «•N˜}4B€¦VÚ !h¸\è한aቀ §Ç‹Ð)3ƒ›°õ»¡4¦¤P7q²§t,ÇÚË4yæ™Ûk/Ó@¤ ãU‰§­q€CÒÔZóG¨¡Mæ@À+e6T—„¥Z4/ú§Ìø…7
+rS˜ðí¯ä”¢h¦RDN)
+ûŸ¶FBÃ!@±ù‡xevǸ_kžé9«öuT‚JÆʖ}­”VyŽ©ú¹‡ ÷v–è!<— ë¿%bÊԃJҔùôåXe ˜<MÎi8ð,®³Ö²/û¥­(käË÷43„³>FF-½}2õ¦Yõ†¶úCWêV"$"^×]-Ô@N+p)_Y½5Ë2³!Ð.ˆ‚d:¹ ì¥È쌨w=1øW³Jڗ2\ãêáìùçôá-
+Õò­ƒÕŒ²gx!WNÑ"“@®¦Èp¬dò±3Ø=‹ÜµÊ«
+4½²-w9ÛôÒ/eŽqÃÁ
+ÜQÔôÊ$Xã‰êØÀý
+ѝñ
+Öb%û7^1TÀ;óméã•Þ;KHÕÏ‘,Ô9Õv†_»›JJmºa“/µvàzu÷
+¬V«~Pr^\ÛÒ,Ã)•|“æ‹U–“(fŠ²U´)B}ðÓ.,©IRܒîM>sšÕˆ´r¼®ýøØ^w}8ôüƒÄâö\à lß8IU‹I07‡®ˆÖè£
+Iµ XEA“+i[r©’TÜô×÷Îãξ—…u¥™Ùû<÷œ¸_ºvœ:w|όÞDžPۍ³í݃&~lfm†çs1hÇÀu [¢‰›Ên>`‡Meù°ôÑݒØfm‡f´A¹¤«í0ô6(™®Êjƒ²Áª'3¤ÑFaÓ·ñ2m
+¨¹1ƒvHõ‹¶o¶:¢i+Ó샘ìÖ0¨Š’)›"Í$U”ì–æ3ª­ùLÒ=&šªeµSÛqz{°ã4É°*±,µ­¢©D8¢
+sѷєlȌuˆhÙ±ëî´m¾íD"½îÛªY˜žÉU³N];AZÌUߦØ'¦6¯Nή·Ëûù_þñ¡¬ŠŸ~:{C4£Î£³ß%?ÿLÞ\œŸ¼¹>ɉûowwröË#w{röNÁë[2‡HsM®—ä„
+
+þq޹ޜ̮Šey[.‡r[íO¯ÿyòöãùà·sïoóÛîyÆÃó4<Oýóá¨{þ“{Ñy!ý1H™pŽ\¯NfÅÎýͽ·Â­”ñ·Ý{œ±ø§ín³¨–Å„«
+(¬¥®«2|ÆzO-¾ºñ¬óõ¿)â7a$Â'ÿx(^¹?B¿Yˆ÷;9aY®Ñ!âþtöN„œçî2¼¢¨?ÕÖԛrUËôbMöËEU•ÕÝT ŽÌæ¼I*.|ÃJÿ9…åužÃiÉý§®àqòv]lŠêà]0
+»îƒrgœÐ£ñÌÇ?֋Ù{ðº:x·I^žr™3iG}×fÌ÷åÝý\m±?Xha âÆF§|ïäØ
+K±,b°š‡`]ŸË±`¹õg¤ïÀpFiYmÈïå¾ì}ÜP}k~\2ôi]õb_ìȪܮ
+r3ûüáâæt*G֗0ã9²"挭ù¡¡a¹û!¸ò©7Z
+âˆóÓôá{±‹™³¹Â—ÃmâQ…Æ6&æx~<«›/‹uù |ªñ~.ýÿžì+ÈìaáօvMƒö†¬õ@|b­ùNùãnÀ_ùbªbæz¤í±žS¯ô\E”®'îrq¨bVXêŽ^÷ Ǒil,ÀN7^û³}±ÌHµÝ”SSãô Ãí*Å»²X¯È—ru¸•ˆ—4†d`4†4AºÆ
+ŠŠ”UÀҗ››S²8Úø¥t¿œˆK=éì¹ÆXPJÛÑhG|ÛïJ@¨ómuØ-öˆ{”†ÕþâH )SJE仟ÉäãåŔ¿ÂÐN·
+¡hŽ×#hŠçȪŠê.îAp˜
+É3Ð3“þ
+üÅΑ åº£À¬;!™ÃŠñ¢c×{ۀ–F‡©žöWDi¹ÆȀ<F‡õÑõ,`•0DŽF3±F~0Dò==¼OòÓ­gTØØ6³bleÇP¸Š4_*‰,åüâò×ð2yÿ~* êóXÚ¯vaðÀ3†¬ŸL²ÉeñïGN=M ·63"g½4¡rP8¢9ƒŸQ¼r$&ù²>tČoÌëAÑöÍ]÷M)þW $ðœµÔÌ^y„Ò@ØC’òÌØy‰ Mã¸(†’á¥ü|qNÈvG৳—”E‡i ôÀrsäȟ[âK`?’UáàzO¶yØmWËYn«Ûò.éH$V0 i¢ÛÀ¸äۑ,ªÕd‰<éã]ü•‘â1–­šÓº\ôêPk¬qQ¹/Ü6‡¦œÑn婉%¤#†@cÈÉèøUÖ¢•œt9÷%6•K°û38“€]¶€§N™‚¾_­‹€°,§qzµ¤Ãu& ^t