Otto - riadiaci program v.2

From DT^2
Revision as of 11:50, 3 August 2018 by 158.195.189.186 (talk)
Jump to: navigation, search

Program umožňuje priame riadenie robota (aj cez BlueTooth). Teraz už funguje aj na pinoch 2,4 a môže sa naraz programovať aj komunikovať.

Na komunikáciu s robotom môžete použiť napr. program Putty: putty.exe.

klaves servo pin Kalibracia
a/q ľavá ruka 10 4
;/p pravá ruka 11 5
z/x ľavá noha 9 3
,/. pravá noha 6 2
d/c ľavá päta 5 1
k/m pravá päta 3 0
1/9 zníž/zvýš rýchlosť pohybu -
TXD BT 2
RXD BT 4
TRIG UZ 7
ECHO UZ 8
Sirena 12

Ďalej umožňuje

  • kalibrovať strednú polohu servomotorov (pomocou klávesu H)
    • pomocou + a - najdeme nulovu polohu serva
    • eneter ideme na dalsie servo
    • ukoncime E ulozenie do eprom
    • potvrdime Y
  • kalibrovať limity pre všetky stupne voľnosti (pomocou klávesu J), zobrazenie celej kalibrácie: kláves G
  • celú kalibráciu je možné zapísať do trvalej pamäte EEPROM pomocou klávesu E (používať opatrne!), po zapnutí sa automaticky načíta
  • pozdraví po klávese -, ruky dá hore na kláves R
  • načíta choreografiu po klávese @,
  • zobrazí načítanú choreografiu na kláves ? a
  • zatancuje načítanú choreografiu - kláves t.
  • Na klávesách 3-6 je možné nastaviť rôznu kombináciu (funkcie kombinacia1() - kombinacia4()).
  • Kláves U testuje ultrazvuk
  • Medzera resetne všetky servo motory do strednej polohy.

Pozrite si (a skopírujte si) príklady choreografií: Otto - príklady choreografií

  1 #include <Servo.h>
  2 #include <EEPROM.h>
  3 
  4 #define ECHO_BT_TO_USB 1
  5 
  6 #define US_TRIG  7
  7 #define US_ECHO  8
  8 
  9 #define BT_RX   2 
 10 #define BT_TX   4
 11 
 12 #define SIRENA 12
 13 
 14 //maximalna dlzka choreografie
 15 #define CHOREO_LEN 200
 16 
 17 // cisla pinov, kde su zapojene servo motory
 18 #define PIN_SERVO_LAVA_RUKA   10 
 19 #define PIN_SERVO_PRAVA_RUKA  11
 20 #define PIN_SERVO_LAVA_NOHA   9
 21 #define PIN_SERVO_PRAVA_NOHA  6
 22 #define PIN_SERVO_LAVA_PATA   5
 23 #define PIN_SERVO_PRAVA_PATA  3
 24 
 25 #define S1 3
 26 #define S2 5
 27 #define S3 6
 28 #define S4 9
 29 #define S5 10
 30 #define S6 11
 31 #define SIRENA 12
 32 
 33 //maximalna dlzka choreografie
 34 #define CHOREO_LEN 200
 35 
 36 // tu su serva cislovane 1-6
 37 #define SERVO_LAVA_RUKA   5 
 38 #define SERVO_PRAVA_RUKA  6
 39 #define SERVO_LAVA_NOHA   4
 40 #define SERVO_PRAVA_NOHA  3
 41 #define SERVO_LAVA_PATA   2
 42 #define SERVO_PRAVA_PATA  1
 43 
 44 // ak su niektore serva naopak, je tu jednotka
 45 uint8_t servo_invertovane[6] = {0, 0, 1, 1, 0, 1};
 46 
 47 // znaky, ktorymi sa ovladaju jednotlive stupne volnosti
 48 char znaky_zmien[] = {'a', 'q', ';', 'p', 'z', 'x', ',', '.', 'd', 'c', 'k', 'm' };
 49 // co robia jednotlive znaky (znamienko urcuje smer)
 50 int8_t zmeny[] = {SERVO_LAVA_RUKA, -SERVO_LAVA_RUKA, 
 51                   SERVO_PRAVA_RUKA, -SERVO_PRAVA_RUKA, 
 52                   -SERVO_LAVA_NOHA, SERVO_LAVA_NOHA, 
 53                   -SERVO_PRAVA_NOHA, SERVO_PRAVA_NOHA, 
 54                    SERVO_LAVA_PATA, -SERVO_LAVA_PATA, 
 55                    SERVO_PRAVA_PATA, -SERVO_PRAVA_PATA }; 
 56 
 57 // sem si mozno ulozit svoju kalibraciu
 58 //uint8_t prednastavena_kalibracia[] = { 78, 69, 83, 80, 50, 67 };
 59 uint8_t prednastavena_kalibracia[] = { 90, 90, 90, 90, 90, 90 };
 60 
 61 uint8_t dolny_limit[] = {0, 0, 0, 0, 0, 0, 0, 0};
 62 uint8_t horny_limit[] = {180, 180, 180, 180, 180, 180};
 63 
 64 Servo s[6];
 65 
 66 uint16_t ch_time[CHOREO_LEN];
 67 uint8_t ch_servo[CHOREO_LEN];
 68 uint8_t ch_val[CHOREO_LEN];
 69 int ch_len;
 70 uint8_t kalib[6];
 71 int stav[6];
 72 int krok;
 73 
 74 void setup() {
 75   Serial.begin(9600);
 76   init_serial(9600);
 77   init_ultrasonic();
 78 
 79   randomSeed(analogRead(1));
 80   s[0].attach(PIN_SERVO_PRAVA_PATA);
 81   s[1].attach(PIN_SERVO_LAVA_PATA);
 82   s[2].attach(PIN_SERVO_PRAVA_NOHA);
 83   s[3].attach(PIN_SERVO_LAVA_NOHA);
 84   s[4].attach(PIN_SERVO_PRAVA_RUKA);
 85   s[5].attach(PIN_SERVO_LAVA_RUKA);
 86   precitaj_kalibraciu_z_EEPROM();
 87   for (int i = 0; i < 6; i++)
 88   {
 89     kalib[i] = prednastavena_kalibracia[i];
 90     stav[i] = kalib[i];
 91     s[i].write(stav[i]);
 92   }
 93   ch_len = 0;
 94   krok = 7;
 95   ahoj();
 96   ruky2();
 97   delay(100);  
 98   serial_println("\r\n  Otto DTDT");
 99 }
100 
101 void loop() {
102   char z = -1;
103   if (serial_available()) z = serial_read();
104 #ifdef ECHO_BT_TO_USB
105     if (Serial.available()) z = Serial.read();
106 #endif  
107   
108   if (z != -1)
109   { 
110     if (pohyb_znakom(z)) return;   
111     else if (pohyb_kombinacia(z)) return; 
112     else if (z == '@') nacitaj_choreografiu();
113     else if (z == '?') vypis_choreografiu();
114     else if (z == 't') zatancuj_choreografiu();
115     else if (z == '-') ahoj();
116     else if (z == ' ') reset();
117     else if (z == 'H') kalibruj();
118     else if (z == 'J') nastav_limity();
119     else if (z == 'G') vypis_kalibraciu();
120     else if (z == 'L') nacitaj_kalibraciu();
121     else if (z == 'E') zapis_kalibraciu_do_EEPROM();
122     else if (z == 'R') ruky();
123     else if (z == '9') zvys_krok();
124     else if (z == '1') zniz_krok();
125     else if (z == 'U') test_ultrazvuk();
126   }
127   int16_t d = measure_distance();
128   if (d < 10) menu_ultrasonic_request();
129 }
130 
131 void test_ultrazvuk()
132 {
133   int i = 0;
134   while ((serial_available() == 0) && (Serial.available() == 0))
135   {
136     serial_println_num(measure_distance());
137     delay(100);
138   }
139   serial_read();
140 }
141 
142 void menu_ultrasonic_request()
143 {
144   uint32_t tm = millis();
145   int d = measure_distance();
146   int count;
147   while ((millis() - tm < 3000) && (d < 15) & (count < 10)) 
148   {
149     delay(10);
150     d = measure_distance();
151     if (d == 10000) count++;
152     else count = 0;
153   }
154   if (millis() - tm >= 3000)
155     ultrasonic_menu();
156 }
157 
158 void ultrasonic_menu()
159 {
160   int selection = 0;
161   tone(SIRENA, 880, 200);
162   
163   do {  
164     int count = 0;
165     do { 
166       int32_t d = measure_distance();
167       if (d == 10000) continue;
168       if (d >= 20) count++;
169       else count = 0;
170       delay(10);
171     } while (!serial_available() && !Serial.available() && (count < 20));
172     
173     tone(SIRENA, 440, 200);
174     uint32_t tm = millis();
175     while ((measure_distance() > 15) && (millis() - tm < 1500) && !serial_available() && !Serial.available()) delay(10);
176     if (millis() - tm >= 1500) 
177     {
178       tone(SIRENA, 2000, 50);
179       menu_command(selection);
180       return;
181     }       
182     selection++;
183     for (int i = 0; i < selection; i++)
184     {
185       tone(SIRENA, 1261, 50);
186       delay(250);
187     }
188   } while (!serial_available() && !Serial.available());
189   while (serial_available()) serial_read();
190   while (Serial.available()) Serial.read();
191 }
192 
193 void menu_command(int cmd)
194 {
195   if (cmd == 2) ahoj();
196   serial_println_num(cmd);
197 }
198 
199 void precitaj_kalibraciu_z_EEPROM()
200 {
201   uint8_t value = EEPROM.read(1);
202   if (value != '~') return;
203   for (int i = 2; i < 8; i++)
204     prednastavena_kalibracia[i - 2] = EEPROM.read(i);
205   for (int i = 0; i < 6; i++)
206     dolny_limit[i] = EEPROM.read(i + 9);
207   for (int i = 0; i < 6; i++)
208     horny_limit[i] = EEPROM.read(i + 15);    
209 }
210 
211 char read_char()
212 {
213   while (!serial_available() && !Serial.available());
214   if (serial_available()) return serial_read();
215   else return Serial.read();
216 }
217 
218 void zapis_kalibraciu_do_EEPROM()
219 {
220   serial_print("Naozaj chces zapisat kalibraciu do EEPROM? [Y/n]: ");
221   char odpoved = read_char();
222   serial_println_char(odpoved);
223   if (odpoved == 'Y') 
224   {
225     EEPROM.write(1, '~');
226     for (int i = 2; i < 8; i++)
227       EEPROM.write(i, kalib[i - 2]);
228     for (int i = 0; i < 6; i++)
229       EEPROM.write(9 + i, dolny_limit[i]);
230     for (int i = 0; i < 6; i++)
231       EEPROM.write(15 + i, horny_limit[i]);
232     serial_println("ok");
233   }
234 }
235 
236 void pipni()
237 {
238   tone(SIRENA, 1568, 50);
239   delay(100);
240   tone(SIRENA, 1357, 50);
241 }
242 
243 void ruky()
244 {
245   int odloz_krok = krok;
246   delay(500);
247   krok = 90;
248   pohyb(SERVO_LAVA_RUKA);    
249   pohyb(SERVO_PRAVA_RUKA);
250   delay(1000);
251   krok = 180;
252   pohyb(-SERVO_LAVA_RUKA);    
253   pohyb(-SERVO_PRAVA_RUKA);
254   delay(1000);
255   krok = odloz_krok;
256   pipni();
257 }
258 
259 void ruky2()
260 {
261   int odloz_krok = krok;
262   delay(500);
263   krok = 180;
264   pohyb(SERVO_LAVA_RUKA);    
265   pohyb(SERVO_PRAVA_RUKA);
266   delay(1000);
267   krok = 90;
268   pohyb(-SERVO_LAVA_RUKA);    
269   pohyb(-SERVO_PRAVA_RUKA);
270   delay(1000);
271   krok = odloz_krok;
272   pipni();
273 }
274 
275 void ahoj()
276 {
277   tone(SIRENA, 1568, 50);
278   delay(70);
279   tone(SIRENA, 1175, 30);
280   delay(50);
281   tone(SIRENA, 880, 30);
282   delay(50);
283   tone(SIRENA, 1047, 50);
284   delay(70);
285   tone(SIRENA, 1245, 30);
286   delay(150);
287   tone(SIRENA, 1568, 50);
288   delay(100);
289   if (random(10) > 4) tone(SIRENA, 1357, 50);
290   else tone(SIRENA, 1047, 50);
291 }
292 
293 void nastav_koncatinu(int8_t servo, uint8_t poloha)
294 {
295   int8_t srv = (servo > 0)?servo:-servo;
296   srv--;
297   poloha += kalib[srv] - 90;
298   if (poloha > 180) poloha = 180;
299   if (poloha < 0) poloha = 0;
300   stav[srv] = poloha;
301   s[srv].write(stav[srv]);
302 }
303 
304 void pohyb(int8_t servo)
305 {
306   int8_t srv = (servo > 0)?servo:-servo;
307   srv--;
308   if (servo_invertovane[srv]) servo = -servo;
309   if (servo > 0)
310   {
311     if (stav[srv] <= horny_limit[srv] - krok) stav[srv] += krok;
312     else stav[srv] = horny_limit[srv];
313     s[srv].write(stav[srv]);
314   }
315   else if (servo < 0)
316   {
317     if (stav[srv] >= dolny_limit[srv] + krok) stav[srv] -= krok; 
318     else stav[srv] = dolny_limit[srv];
319     s[srv].write(stav[srv]);      
320   }
321 }
322 
323 uint8_t pohyb_znakom(char z)
324 {
325   for (int i = 0; i < 12; i++)
326   {
327     if (z == znaky_zmien[i])
328     {
329       int8_t servo = zmeny[i];
330       pohyb(servo);
331     }
332   }
333 }
334 
335 void kombinacia1()
336 {
337   pohyb(SERVO_LAVA_NOHA);
338   pohyb(-SERVO_PRAVA_PATA);
339 }
340 
341 void kombinacia2()
342 {
343   pohyb(SERVO_PRAVA_NOHA);
344   pohyb(-SERVO_LAVA_PATA);
345 }
346 
347 void kombinacia3()
348 {
349    pohyb(SERVO_LAVA_RUKA); 
350    pohyb(SERVO_PRAVA_RUKA); 
351 }
352 
353 void kombinacia4()
354 {
355    pohyb(-SERVO_LAVA_RUKA); 
356    pohyb(-SERVO_PRAVA_RUKA); 
357 }
358 
359 int pohyb_kombinacia(char z)
360 {
361   if (z == '3') kombinacia1();
362   else if (z == '4') kombinacia2();
363   else if (z == '5') kombinacia3();
364   else if (z == '6') kombinacia4();
365   else return 0;
366   return 1;
367 }
368 
369 int nacitajCislo()
370 {
371   int num = 0;
372   int z;
373   do {
374     z = read_char();
375     if (z == '#') while (z != 13) z = read_char();
376   } while ((z < '0') || (z > '9'));
377   while ((z >= '0') && (z <= '9'))
378   {
379     num *= 10;
380     num += (z - '0');
381     do { z = read_char(); if (z == -1) delayMicroseconds(10); } while (z < 0);
382   }
383   return num;
384 }
385 
386 void nacitaj_choreografiu()
387 {
388   ch_len = 0;
389   int tm;
390   do { 
391     tm = nacitajCislo();
392     ch_time[ch_len] = tm;
393     ch_servo[ch_len] = nacitajCislo();
394     ch_val[ch_len] = nacitajCislo();
395     ch_len++;
396   if (ch_len == CHOREO_LEN) break;
397   } while (tm > 0);
398   pipni();  
399 }
400 
401 void vypis_choreografiu()
402 {
403   for (int i = 0; i < ch_len; i++)
404   {
405     serial_print_num(ch_time[i]);
406     serial_print(" ");
407     serial_print_num(ch_servo[i]);
408     serial_print(" ");
409     serial_println_num(ch_val[i]);      
410   }
411   pipni();
412 }
413 
414 void zatancuj_choreografiu()
415 {
416   for (int i = 0; i < ch_len - 1; i++)
417   {
418     delay(ch_time[i]);
419     nastav_koncatinu(ch_servo[i], ch_val[i]);
420   }
421   if (ch_len > 0) stav[ch_servo[ch_len - 1]] = ch_val[ch_len - 1];
422   pipni();
423   while (serial_available()) serial_read();
424   while (Serial.available()) Serial.read();
425 }
426 
427 void reset()
428 {
429   for (int i = 0; i < 6; i++) 
430   {
431     stav[i] = kalib[i];
432     s[i].write(kalib[i]);
433   }
434   pipni();
435 }
436 
437 uint8_t nalad_hodnotu_serva(uint8_t servo, uint8_t hodnota)
438 {
439     serial_print(" (+/-/ENTER): ");
440     serial_println_num(hodnota);
441     s[servo].write(hodnota);
442     char z;
443     do {
444       z = read_char();
445       if ((z == '+') && (hodnota < 180)) hodnota++;
446       else if ((z == '-') && (hodnota > 0)) hodnota--; 
447       if ((z == '+') || (z == '-'))
448       {
449         serial_print_num(hodnota); serial_print_char('\r'); 
450         s[servo].write(hodnota);
451       }
452     } while (z != 13);
453     return hodnota;
454 }
455 
456 void kalibruj()
457 {
458   for (int i = 0; i < 6; i++)
459   {
460     serial_print_num(i);
461     kalib[i] = nalad_hodnotu_serva(i, kalib[i]);
462     serial_print_num(i);
463     serial_print(": ");
464     serial_println_num(kalib[i]);
465   }
466   for (int i = 0; i < 6; i++) { serial_print_num(kalib[i]); serial_print(" "); }
467   serial_println("ok");
468   pipni();
469 }
470 
471 void nastav_limity()
472 {
473   for (int i = 0; i < 6; i++)
474   {
475     serial_print_num(i);
476     serial_print("dolny");
477     dolny_limit[i] = nalad_hodnotu_serva(i, dolny_limit[i]);
478     serial_print_num(i);
479     serial_print(" dolny: ");
480     serial_println_num(dolny_limit[i]);
481     s[i].write(kalib[i]);
482 
483     serial_print_num(i);
484     serial_print("horny");
485     horny_limit[i] = nalad_hodnotu_serva(i, horny_limit[i]);
486     serial_print_num(i);
487     serial_print(" horny: ");
488     serial_println_num(horny_limit[i]);
489     s[i].write(kalib[i]);
490   }
491   for (int i = 0; i < 6; i++) { serial_print_num(dolny_limit[i]); serial_print("-"); serial_print_num(horny_limit[i]); serial_print(" "); }
492   serial_println("ok");
493   pipni();
494 }
495 
496 void vypis_kalibraciu()
497 {
498   serial_print("stredy: ");
499   for (int i = 0; i < 6; i++) { serial_print_num(kalib[i]); serial_print(" "); }
500   serial_println();
501   serial_print("dolny limit: ");
502   for (int i = 0; i < 6; i++) { serial_print_num(dolny_limit[i]); serial_print(" "); }
503   serial_println();
504   serial_print("horny limit: ");
505   for (int i = 0; i < 6; i++) { serial_print_num(horny_limit[i]); serial_print(" "); }
506   serial_println();
507 }
508 
509 void nacitaj_kalibraciu()
510 {
511   int tm;
512   for (int i = 0; i < 6; i++) 
513     kalib[i] = nacitajCislo();
514   vypis_kalibraciu();
515   serial_println("ok");
516   pipni();
517 }
518 
519 void zvys_krok()
520 {
521   if (krok < 180) krok++;
522   serial_print("krok: ");
523   serial_println_num(krok);
524 }
525 
526 void zniz_krok()
527 {
528   if (krok > 0) krok--;
529   serial_print("krok: ");
530   serial_println_num(krok);
531 }
532 
533 // nasleduje softverova implementacia serioveho portu
534 #define SERIAL_STATE_IDLE      0
535 #define SERIAL_STATE_RECEIVING 1
536 #define SERIAL_BUFFER_LENGTH   20
537 
538 static volatile uint8_t serial_state;
539 static uint8_t serial_buffer[SERIAL_BUFFER_LENGTH];
540 static volatile uint8_t serial_buf_wp, serial_buf_rp;
541 
542 static volatile uint8_t receiving_byte;
543 
544 static volatile uint32_t time_startbit_noticed;
545 static volatile uint8_t next_bit_order;
546 static volatile uint8_t waiting_stop_bit;
547 static uint16_t one_byte_duration;
548 static uint16_t one_bit_duration;
549 static uint16_t one_bit_write_duration;
550 static uint16_t half_of_one_bit_duration;
551 
552 void init_serial(uint32_t baud_rate)
553 {
554   pinMode(2, INPUT);
555   pinMode(4, OUTPUT);
556   
557   serial_state = SERIAL_STATE_IDLE;
558   
559   one_byte_duration = 9500000 / baud_rate;
560   one_bit_duration = 1000000 / baud_rate;
561   one_bit_write_duration = one_bit_duration - 1;
562   half_of_one_bit_duration = 500000 / baud_rate;
563   
564   PCMSK2 |= 4; //PCINT18;
565   PCIFR &= ~4; //PCIF2;
566   PCICR |= 4; // PCIE2;
567 }
568 
569 ISR(PCINT2_vect)
570 {
571   uint32_t tm = micros();
572   if (serial_state == SERIAL_STATE_IDLE)
573   {    
574     time_startbit_noticed = tm;
575     serial_state = SERIAL_STATE_RECEIVING;
576     receiving_byte = 0xFF;
577     next_bit_order = 0;
578   }
579   else if (tm - time_startbit_noticed > one_byte_duration)
580   {
581       serial_buffer[serial_buf_wp] = receiving_byte;
582       serial_buf_wp++;
583       if (serial_buf_wp == SERIAL_BUFFER_LENGTH) serial_buf_wp = 0;
584       time_startbit_noticed = tm;
585       receiving_byte = 0xFF;
586       next_bit_order = 0;
587   }
588   else if (PIND & 4) 
589   {
590      int8_t new_next_bit_order = (tm - time_startbit_noticed - half_of_one_bit_duration) / one_bit_duration;
591      while (next_bit_order < new_next_bit_order)
592      {  
593         receiving_byte &= ~(1 << next_bit_order);
594         next_bit_order++;
595      }
596      if (next_bit_order == 8)
597      { 
598         serial_buffer[serial_buf_wp] = receiving_byte;
599         serial_buf_wp++;
600         if (serial_buf_wp == SERIAL_BUFFER_LENGTH) serial_buf_wp = 0;
601         serial_state = SERIAL_STATE_IDLE;
602      }        
603   } else 
604       next_bit_order = (tm - time_startbit_noticed - half_of_one_bit_duration) / one_bit_duration;
605 }
606 
607 uint8_t serial_available()
608 {
609   cli();
610   if (serial_buf_rp != serial_buf_wp) 
611   {
612     sei();
613     return 1;
614   }
615   if (serial_state == SERIAL_STATE_RECEIVING)
616   {
617     uint32_t tm = micros();
618     if (tm - time_startbit_noticed > one_byte_duration)
619     {      
620       serial_state = SERIAL_STATE_IDLE;
621       serial_buffer[serial_buf_wp] = receiving_byte;
622       serial_buf_wp++;
623       if (serial_buf_wp == SERIAL_BUFFER_LENGTH) serial_buf_wp = 0;
624       sei();
625       return 1;
626     }
627   }
628   sei();
629   return 0;
630 }
631 
632 int16_t serial_read()
633 {
634   cli();
635   if (serial_buf_rp != serial_buf_wp)
636   {
637     uint8_t ch = serial_buffer[serial_buf_rp];
638     serial_buf_rp++;
639     if (serial_buf_rp == SERIAL_BUFFER_LENGTH) serial_buf_rp = 0;
640     sei();
641     return ch;
642   }
643 
644   if (serial_state == SERIAL_STATE_RECEIVING)
645   {
646     uint32_t tm = micros();
647     if (tm - time_startbit_noticed > one_byte_duration)
648     {
649       uint8_t ch = receiving_byte;
650       serial_state = SERIAL_STATE_IDLE;  
651       sei();
652       return ch;
653     }
654   }
655   sei();
656   return -1;
657 }
658 
659 void serial_write(uint8_t ch)
660 {
661 #ifdef ECHO_BT_TO_USB
662   Serial.print((char)ch);
663 #endif
664   PORTD &= ~16;
665   delayMicroseconds(one_bit_write_duration);
666   for (uint8_t i = 0; i < 8; i++)
667   {
668     if (ch & 1) PORTD |= 16;
669     else PORTD &= ~16;
670     ch >>= 1;
671     delayMicroseconds(one_bit_write_duration);
672   }
673   PORTD |= 16;
674   delayMicroseconds(one_bit_write_duration);
675   delayMicroseconds(one_bit_write_duration);
676   delayMicroseconds(one_bit_write_duration);
677   delayMicroseconds(one_bit_write_duration);
678   delayMicroseconds(one_bit_write_duration);
679 }
680 
681 uint16_t serial_readln(uint8_t *ln, uint16_t max_length)
682 {
683   uint16_t len;
684   uint16_t ch;
685   do {
686     ch = serial_read();
687     if (ch == 13) continue;
688   } while (ch == -1);
689 
690   do {
691     if ((ch != 13) && (ch != 10) && (ch != -1)) 
692     {
693       *(ln++) = ch;
694       max_length--;
695       len++;
696     }    
697     ch = serial_read();
698   } while ((ch != 13) && max_length);
699   *ln = 0;
700   return len;
701 }
702 
703 void serial_print_num(int32_t number)
704 {
705   if (number < 0) 
706   {
707     serial_write('-');
708     number = -number;
709   }
710   int32_t rad = 1;
711   while (number / rad) rad *= 10;
712   if (number > 0) rad /= 10;
713   while (rad)
714   {
715     serial_write((char)('0' + (number / rad)));
716     number -= (number / rad) * rad;
717     rad /= 10;
718   }  
719 }
720 
721 void serial_print_char(char ch)
722 {
723   serial_write(ch);  
724 }
725 
726 void serial_print(const uint8_t *str)
727 {
728   while (*str) serial_write(*(str++));
729 }
730 
731 void serial_println(const uint8_t *str)
732 {
733   serial_print(str);
734   serial_write(13);
735   serial_write(10);
736 }
737 
738 void serial_println_num(int32_t number)
739 {
740   serial_print_num(number);
741   serial_println();
742 }
743 
744 void serial_println_char(char ch)
745 {
746   serial_write(ch);
747   serial_println();
748 }
749 
750 void serial_println()
751 {
752   serial_write(13);
753   serial_write(10);
754 }
755 
756 // nasleduje citanie z utltazvukoveho senzora
757 
758 static volatile uint32_t pulse_start;
759 static volatile int16_t distance;
760 static volatile uint8_t new_distance;
761 
762 void init_ultrasonic()
763 {
764   pinMode(US_ECHO, INPUT);
765   pinMode(US_TRIG, OUTPUT);
766   
767   PCMSK0 |= 1; //PCINT0;
768   PCIFR &= ~1; //PCIF0;
769   PCICR |= 1; // PCIE0;  
770 }
771 
772 ISR(PCINT0_vect)
773 {
774   if (PINB & 1) pulse_start = micros();
775   else 
776   {
777     distance = (int16_t)((micros() - pulse_start) / 58);
778     new_distance = 1;
779   }
780 }
781 
782 void start_distance_measurement()
783 {
784   distance = 10000;
785   new_distance = 0;
786   digitalWrite(US_TRIG, HIGH);
787   delayMicroseconds(10);
788   digitalWrite(US_TRIG, LOW);
789 }
790 
791 void wait_for_distance_measurement_to_complete()
792 {
793   uint8_t counter = 0;
794   while ((counter < 20) && !new_distance) 
795   {
796     delay(1);
797     counter++;
798   }
799   if (counter == 20)
800   {
801     pinMode(US_ECHO, OUTPUT);
802     digitalWrite(US_ECHO, HIGH);
803     delayMicroseconds(10);
804     digitalWrite(US_ECHO, LOW);
805     pinMode(US_ECHO, INPUT); 
806     delayMicroseconds(5);
807     distance = 10000;
808   }
809 }
810 
811 int16_t measure_distance()
812 {
813   start_distance_measurement();
814   wait_for_distance_measurement_to_complete();
815   return distance;
816 }

V programe puTTy môžete použiť aj tento jednoduchý robotí tanec @ 1000 1 60 1 5 90 1 6 90

1000 1 90 1 5 120 1000 1 120 1 6 120 1 6 90 1 2 120 1 5 90 100 1 90 1 5 45 100 2 90 1 6 45 1000 2 60 1 5 120 1000 2 90 1 6 120 1000 2 120 1 1 120 100 2 90 1 6 90 100 1 90 1 5 90 0 0 0 ak toto vložíte do textove dokumentu a zkopírujete, pravým kliknitímna plochu v puTTy a následným stlačením tlačidla T váš robot začne tancovať