Otto - riadiaci program v.4
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.
Pripojenie na vývody Arduina:
servo | pin |
---|---|
ľavá ruka | 10 |
pravá ruka | 11 |
ľavá noha | 9 |
pravá noha | 6 |
ľavá päta | 5 |
pravá päta | 3 |
TXD BlueTooth | 2 |
RXD BlueTooth | 4 |
TRIG Ultrazvuk | 7 |
ECHO Ultrazvuk | 8 |
Sirena | 12 |
Číslovanie serva v choreografii:
servo | číslo serva v choreografii |
---|---|
ľavá ruka | 5 |
pravá ruka | 6 |
ľavá noha | 4 |
pravá noha | 3 |
ľavá päta | 2 |
pravá päta | 1 |
klaves | servo/funkcia |
---|---|
a/q | ľavá ruka |
;/p | pravá ruka |
z/x | ľavá noha |
,/. | pravá noha |
d/c | ľavá päta |
k/m | pravá päta |
1/9 | zníž/zvýš rýchlosť pohybu |
H | kalibrovať strednú polohu servomotorov
|
J | kalibrovať limity pre všetky stupne voľnosti (len pre priame riadenie) |
G | zobrazenie celej kalibrácie |
E | celú kalibráciu je možné zapísať do trvalej pamäte EEPROM (používať opatrne! - dá sa prepísať najviac 100000-krát), po zapnutí sa automaticky načíta, treba potvrdiť veľkým Y |
minus | zvukový pozdrav |
R | ruky hore-dole |
@ | načítanie choreografie, pozri príklady a formát |
? | zobrazí načítanú choreografiu (kontrola po @) |
t | zatancuje načítanú choreografiu |
U | testuje ultrazvuk |
S | zobrazí aktuálnu polohu servomotorov (vhodné pri laden |
medzera | reset všetkých motorov do strednej polohy |
3,...,6 | zmiešaný pohyb (treba nastaviť vo funkciách kombinacia1() - kombinacia4()) |
v,b,n,j,h,g,f,s,l,o,i,u,y,r,e,w | zvukové efekty 1-16 |
TAB,*,/,+ | zahrá melódiu 1-4 |
W | zapísať choreografiu do EEPROM (opatrne) |
C | načítať choreografiu z EEPROM |
X | formátovať EEPROM na zápis choreografií (opatrne) |
Pozrite si (a skopírujte si) príklady choreografií: Otto - príklady choreografií
Download: otto3.ino
1 #include <Servo.h>
2 #include <EEPROM.h>
3 #include <avr/pgmspace.h>
4
5 #define ECHO_BT_TO_USB 1
6
7 #define US_TRIG 7
8 #define US_ECHO 8
9
10 #define BT_RX 2
11 #define BT_TX 4
12
13 #define SIRENA 12
14
15 //maximalna dlzka choreografie
16 #define CHOREO_LEN 200
17
18 // cisla pinov, kde su zapojene servo motory
19 #define PIN_SERVO_LAVA_RUKA 10
20 #define PIN_SERVO_PRAVA_RUKA 11
21 #define PIN_SERVO_LAVA_NOHA 9
22 #define PIN_SERVO_PRAVA_NOHA 6
23 #define PIN_SERVO_LAVA_PATA 5
24 #define PIN_SERVO_PRAVA_PATA 3
25
26 #define S1 3
27 #define S2 5
28 #define S3 6
29 #define S4 9
30 #define S5 10
31 #define S6 11
32
33 // tu su serva cislovane 1-6
34 #define SERVO_LAVA_RUKA 5
35 #define SERVO_PRAVA_RUKA 6
36 #define SERVO_LAVA_NOHA 4
37 #define SERVO_PRAVA_NOHA 3
38 #define SERVO_LAVA_PATA 2
39 #define SERVO_PRAVA_PATA 1
40
41 // ak su niektore serva naopak, je tu jednotka
42 uint8_t servo_invertovane[6] = {0, 0, 1, 1, 0, 1};
43
44 // znaky, ktorymi sa ovladaju jednotlive stupne volnosti
45 char znaky_zmien[] = {'a', 'q', ';', 'p', 'z', 'x', ',', '.', 'd', 'c', 'k', 'm' };
46 // co robia jednotlive znaky (znamienko urcuje smer)
47 int8_t zmeny[] = {SERVO_LAVA_RUKA, -SERVO_LAVA_RUKA,
48 SERVO_PRAVA_RUKA, -SERVO_PRAVA_RUKA,
49 -SERVO_LAVA_NOHA, SERVO_LAVA_NOHA,
50 -SERVO_PRAVA_NOHA, SERVO_PRAVA_NOHA,
51 SERVO_LAVA_PATA, -SERVO_LAVA_PATA,
52 SERVO_PRAVA_PATA, -SERVO_PRAVA_PATA };
53
54 // sem si mozno ulozit svoju kalibraciu
55 uint8_t prednastavena_kalibracia[] = { 90, 90, 90, 90, 90, 90 };
56
57 uint8_t dolny_limit[] = {0, 0, 0, 0, 0, 0, 0, 0};
58 uint8_t horny_limit[] = {180, 180, 180, 180, 180, 180};
59
60 Servo s[6];
61
62 uint16_t ch_time[CHOREO_LEN];
63 uint8_t ch_servo[CHOREO_LEN];
64 uint8_t ch_val[CHOREO_LEN];
65 int ch_len;
66 uint8_t kalib[6];
67 int stav[6];
68 int krok;
69 uint8_t spomalenie;
70
71 static volatile int16_t distance;
72
73 void setup() {
74 Serial.begin(9600);
75 init_tone2();
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_LAVA_RUKA);
85 s[5].attach(PIN_SERVO_PRAVA_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 spomalenie = 6;
96 ahoj();
97 ruky2();
98 delay(100);
99 serial_println_flash(PSTR("\r\n Otto DTDT"));
100 }
101
102 void loop() {
103 char z = -1;
104 if (serial_available()) z = serial_read();
105 #ifdef ECHO_BT_TO_USB
106 if (Serial.available()) z = Serial.read();
107 #endif
108
109 if (z != -1)
110 {
111 if (pohyb_znakom(z)) return;
112 else if (pohyb_kombinacia(z)) return;
113 else if (vydaj_zvukovy_efekt(z)) return;
114 else if (ma_zahrat_melodiu(z)) return;
115 else if (z == '@') nacitaj_choreografiu();
116 else if (z == '?') vypis_choreografiu();
117 else if (z == 't') zatancuj_choreografiu(ch_time, ch_servo, ch_val, ch_len);
118 else if (z == '-') ahoj();
119 else if (z == ' ') reset();
120 else if (z == 'H') kalibruj();
121 else if (z == 'J') nastav_limity();
122 else if (z == 'G') vypis_kalibraciu();
123 else if (z == 'L') nacitaj_kalibraciu();
124 else if (z == 'E') zapis_kalibraciu_do_EEPROM();
125 else if (z == 'R') ruky();
126 else if (z == '9') zvys_krok();
127 else if (z == '1') zniz_krok();
128 else if (z == '8') zvys_spomalenie();
129 else if (z == '7') zniz_spomalenie();
130 else if (z == 'U') test_ultrazvuk();
131 else if (z == 'S') zobraz_stav();
132 else if (z == 'W') skus_zapisat_choreografiu_do_EEPROM();
133 else if (z == 'X') skus_naformatovat_EEPROM_choreografie();
134 else if (z == 'C') skus_nacitat_choreografiu_z_EEPROM();
135 }
136 int16_t d = measure_distance();
137 if (d < 10) menu_ultrasonic_request();
138 }
139
140 const uint8_t klavesy_efektov[] PROGMEM = {'v', 'b', 'n', 'j', 'h', 'g', 'f', 's', 'l', 'o', 'i', 'u', 'y', 'r', 'e', 'w'};
141 #define POCET_KLAVES_EFEKTOV 16
142
143 uint8_t vydaj_zvukovy_efekt(char z)
144 {
145 for (int i = 0; i < POCET_KLAVES_EFEKTOV; i++)
146 if (z == pgm_read_byte(klavesy_efektov + i))
147 {
148 zvukovy_efekt(i + 1);
149 return 1;
150 }
151 return 0;
152 }
153
154 uint8_t ma_zahrat_melodiu(char z)
155 {
156 if (z == 9) zahraj_melodiu(1);
157 else if (z == '*') zahraj_melodiu(2);
158 else if (z == '/') zahraj_melodiu(3);
159 else if (z == '+') zahraj_melodiu(4);
160 }
161
162 void efekt1()
163 {
164 uint16_t fre = 100;
165 for (int i = 0; i < 200; i++)
166 {
167 tone2(fre, 2);
168 fre += 10;
169 delay(2);
170 }
171 }
172
173 void efekt2()
174 {
175 uint16_t fre = 2060;
176 for (int i = 0; i < 200; i++)
177 {
178 tone2(fre, 2);
179 fre -= 10;
180 delay(2);
181 }
182 }
183
184 void efekt3()
185 {
186 uint16_t fre;
187 for (int i = 0; i < 200; i++)
188 {
189 fre = random(3000) + 20;
190 tone2(fre, 2);
191 delay(2);
192 }
193 }
194
195 void efekt4()
196 {
197 uint16_t fre = 100;
198 for (int i = 0; i < 200; i++)
199 {
200 (i&1) ? tone2(fre, 2) : tone2(2100 - fre, 2);
201 fre += 10;
202 delay(2);
203 }
204 }
205
206 void efekt5()
207 {
208 uint16_t fre = 100;
209 for (int i = 0; i < 100; i++)
210 {
211 (i&1) ? tone2(fre, 4) : tone2(2100 - fre, 4);
212 fre += 20;
213 delay(4);
214 }
215 }
216
217 void efekt6()
218 {
219 uint16_t d = 12;
220 for (int i = 0; i < 20; i++)
221 {
222 tone2(1760, 10);
223 delay(d);
224 d += 3;
225 }
226 }
227
228 void efekt7()
229 {
230 for (int i = 0; i < 40; i++)
231 {
232 if (i&1) tone2(1760, 10);
233 delay(10);
234 }
235 }
236
237 void efekt8()
238 {
239 uint16_t d = 72;
240 for (int i = 0; i < 20; i++)
241 {
242 tone2(1760, 10);
243 delay(d);
244 d -= 3;
245 }
246 }
247
248 void efekt9()
249 {
250 float fre = 3500;
251 while (fre > 30)
252 {
253 tone2((uint16_t)fre, 2);
254 fre *= 0.97;
255 delay(2);
256 }
257 }
258
259 void efekt10()
260 {
261 float fre = 30;
262 while (fre < 3000)
263 {
264 tone2((uint16_t)fre, 2);
265 fre *= 1.03;
266 delay(2);
267 }
268 }
269
270 void efekt11()
271 {
272 uint16_t fre = 3500;
273 uint16_t d = 42;
274 for (int i = 0; i < 20; i++)
275 {
276 tone2(fre, d);
277 fre -= 165;
278 delay(d);
279 d -= 2;
280 }
281 }
282
283 void efekt12()
284 {
285 float fre = 110;
286 uint8_t d = 42;
287 for (int i = 0; i < 20; i++)
288 {
289 tone2(fre, d);
290 fre += 165;
291 delay(d);
292 d -= 2;
293 }
294 }
295
296 void efekt13()
297 {
298 uint16_t fre = 3400;
299 uint8_t d = 200;
300 uint8_t delta = 1;
301 for (int i = 0; i < 20; i++)
302 {
303 tone2(fre, d);
304 fre -= 165;
305 delay(d);
306 d -= delta;
307 delta++;
308 }
309 tone2(110, 1000);
310 delay(1000);
311 }
312
313 void efekt14()
314 {
315 uint16_t fre = 880;
316 int16_t d = 20;
317 for (int i = 0; i < 20; i++)
318 {
319 tone2(fre, d);
320 delay(d);
321 fre += random(50) - 25;
322 d += random(10) - 5;
323 if (d < 0) d = 1;
324 }
325 }
326
327 void efekt15()
328 {
329 uint16_t fre = 440;
330 int16_t d = 20;
331 for (int i = 0; i < 20; i++)
332 {
333 tone2(fre, d);
334 delay(d);
335 fre += random(25) - 12;
336 d += random(10) - 5;
337 if (d < 0) d = 1;
338 }
339 }
340
341 void efekt16()
342 {
343 uint16_t fre = 1760;
344 int16_t d = 20;
345 for (int i = 0; i < 20; i++)
346 {
347 tone2(fre, d);
348 delay(d);
349 fre += random(100) - 50;
350 d += random(10) - 5;
351 if (d < 0) d = 1;
352 }
353 }
354
355 void zvukovy_efekt(uint8_t cislo)
356 {
357 switch (cislo) {
358 case 1: efekt1(); break;
359 case 2: efekt2(); break;
360 case 3: efekt3(); break;
361 case 4: efekt4(); break;
362 case 5: efekt5(); break;
363 case 6: efekt6(); break;
364 case 7: efekt7(); break;
365 case 8: efekt8(); break;
366 case 9: efekt9(); break;
367 case 10: efekt10(); break;
368 case 11: efekt11(); break;
369 case 12: efekt12(); break;
370 case 13: efekt13(); break;
371 case 14: efekt14(); break;
372 case 15: efekt15(); break;
373 case 16: efekt16(); break;
374 }
375 }
376
377 void test_ultrazvuk()
378 {
379 int i = 0;
380 while ((serial_available() == 0) && (Serial.available() == 0))
381 {
382 serial_println_num(measure_distance());
383 delay(100);
384 }
385 serial_read();
386 }
387
388 void menu_ultrasonic_request()
389 {
390 uint32_t tm = millis();
391 int d = measure_distance();
392 int count = 0;
393 int count2 = 0;
394 while ((millis() - tm < 1500) && ((d < 15) || (count2 < 5)) && (count < 10))
395 {
396 delay(10);
397 d = measure_distance();
398 if (d == 10000) count++;
399 else count = 0;
400 if (d >= 15) count2++;
401 else count2 = 0;
402 if (serial_available() || Serial.available()) return;
403 }
404 if (millis() - tm >= 1500)
405 ultrasonic_menu();
406 }
407
408 void ultrasonic_menu()
409 {
410 int selection = 0;
411 tone2( 880, 200);
412
413 do {
414 int count = 0;
415 do {
416 int32_t d = measure_distance();
417 if (d == 10000) continue;
418 if (d >= 20) count++;
419 else count = 0;
420 delay(10);
421 } while (!serial_available() && !Serial.available() && (count < 20));
422
423 tone2( 440, 200);
424 uint32_t tm = millis();
425 while ((measure_distance() > 15) && (millis() - tm < 1500) && !serial_available() && !Serial.available()) delay(10);
426 if (millis() - tm >= 1500)
427 {
428 tone2( 2000, 50);
429 menu_command(selection);
430 return;
431 }
432 selection++;
433 for (int i = 0; i < selection; i++)
434 {
435 tone2( 1261, 50);
436 delay(250);
437 }
438 } while (!serial_available() && !Serial.available());
439 while (serial_available()) serial_read();
440 while (Serial.available()) Serial.read();
441 }
442
443 void menu_command(int cmd)
444 {
445 if (cmd == 1) vpred();
446 if (cmd == 2) zahraj_melodiu(1);
447 if (cmd == 3) melodia_jedna_druhej();
448 if (cmd == 4) ahoj();
449 if (cmd == 5) zahraj_melodiu(2);
450 if (cmd == 6) zahraj_melodiu(3);
451 if (cmd == 7) zahraj_melodiu(4);
452 serial_println_num(cmd);
453 }
454
455 void melodia_jedna_druhej()
456 {
457 for (int i = 0; i < 2; i++)
458 {
459 tone2(262, 200);
460 delay(200);
461 tone2(330, 200);
462 delay(200);
463
464 tone2(262, 200);
465 delay(200);
466 tone2(330, 200);
467 delay(200);
468
469 tone2(392, 400);
470 delay(400);
471
472 tone2(392, 400);
473 delay(400);
474 }
475 }
476
477 // chodza pre vacsieho dreveneho robota
478 uint16_t chor_time[] = {100,1,1,100,1,1,1,100,1,1,1,100,1,100,1,0};
479 uint8_t chor_servo[] = {1,2,6,4,3,6,5,1,2,6,5,3,4,1,2,0};
480 uint8_t chor_val[] = {48,69,180,104,104,90,0,111,146,0,90,62,69,48,69,0};
481 uint8_t chor_len = 16;
482
483 void vpred()
484 {
485 while (measure_distance() > 30)
486 zatancuj_choreografiu(chor_time, chor_servo, chor_val, chor_len);
487 pipni();
488 reset();
489 }
490
491 void skus_zapisat_choreografiu_do_EEPROM()
492 {
493 serial_print_flash(PSTR("Cislo? [1-3]: "));
494 char odpoved = read_char();
495 if ((odpoved < '1') || (odpoved > '3')) return;
496 serial_println_char(odpoved);
497 uint8_t cislo = odpoved - '0';
498
499 serial_print_flash(PSTR("Zapisat choreografiu do EEPROM c."));
500 serial_print_char(odpoved);
501 serial_print_flash(PSTR("? [Y/n]: "));
502 odpoved = read_char();
503 serial_println_char(odpoved);
504 if (odpoved == 'Y')
505 zapis_choreografiu_do_EEPROM(cislo);
506 }
507
508 void skus_nacitat_choreografiu_z_EEPROM()
509 {
510 serial_print_flash(PSTR("Cislo? [1-3]: "));
511 char odpoved = read_char();
512 if ((odpoved < '1') || (odpoved > '3')) return;
513 serial_println_char(odpoved);
514 uint8_t cislo = odpoved - '0';
515
516 serial_print_flash(PSTR("Precitat choreografiu z EEPROM c."));
517 serial_print_char(odpoved);
518 serial_print_flash(PSTR("? [Y/n]: "));
519 odpoved = read_char();
520 serial_println_char(odpoved);
521 if (odpoved == 'Y')
522 precitaj_choreografiu_z_EEPROM(cislo);
523 }
524
525 void skus_naformatovat_EEPROM_choreografie()
526 {
527 serial_print_flash(PSTR("Formatovat EEPROM choreografii? [Y/n]:"));
528 char odpoved = read_char();
529 serial_println_char(odpoved);
530 if (odpoved == 'Y')
531 naformatuj_EEPROM_choreografie();
532 }
533
534 //EEPROM MAP:
535 // 0: slot number where choreography 3 starts (B3. Real address = B3 x 4)
536 // 1: marker '~' indicates calibration is already stored in EEPROM and will be loaded on startup
537 // 2-8: servo calibration (central points to be used instead of default 90)
538 // 9-14: lower limit for direct control for all 6 servos
539 // 15-20: upper limit for direct control for all 6 servos
540 // 21: number of steps in choreography 1 (L1) 0=choreography not in memory
541 // 22: number of steps in choreography 2 (L2) 0=not in memory
542 // 23: number of steps in choreography 3 (L3) 0=not in memory
543 // 24..(L1 x 4 + 23) choreography1 tuplets (uint16,uint8,uint8) x L1
544 // (1024 - L2 x 4)..1023 choreography2 same as above
545 // B3 x 4..(B3 x 4 + L3 x 4 - 1) choreography 3 same as above
546 void zapis_choreografiu_do_EEPROM(int slot)
547 {
548 uint8_t b3 = EEPROM.read(0);
549 uint8_t len1 = EEPROM.read(21);
550 uint8_t len2 = EEPROM.read(22);
551 uint8_t len3 = EEPROM.read(23);
552 uint16_t wp = 65535;
553
554 if ((len1 > CHOREO_LEN) || (len2 > CHOREO_LEN) || (len3 > CHOREO_LEN) || (b3 > 250 - len3) || ((len1 > b3) && (b3 != 0)) || (len3 + b3 > 250 - len2) || (len1 + len2 > 250))
555 b3 = len1 = len2 = len3 = 0;
556
557 if (slot == 1)
558 {
559 if (((ch_len < b3) || (len3 == 0)) && (ch_len + len2 + len3 <= 250))
560 {
561 EEPROM.write(21, ch_len);
562 wp = 24;
563 }
564 }
565 else if (slot == 2)
566 {
567 if ((250 - b3 - len3 > ch_len) && (ch_len + len1 + len3 <= 250))
568 {
569 EEPROM.write(22, ch_len);
570 wp = 1000 - ch_len * 4;
571 }
572 }
573 else if (slot == 3)
574 {
575 if (ch_len + len1 + len2 <= 250)
576 {
577 EEPROM.write(23, ch_len);
578 EEPROM.write(0, (len1 - len2) / 2 + 125);
579 wp = 4 * ((len1 - len2) / 2 + 125);
580 }
581 }
582
583 if (wp == 65535)
584 serial_println_flash(PSTR("not enough space"));
585 else
586 {
587 for (int i = 0; i < ch_len; i++)
588 {
589 EEPROM.write(wp + 4 * i, ch_time[i] & 255);
590 EEPROM.write(wp + 1 + 4 * i, ch_time[i] >> 8);
591 EEPROM.write(wp + 2 + 4 * i, ch_servo[i]);
592 EEPROM.write(wp + 3 + 4 * i, ch_val[i]);
593 }
594 serial_println_flash(PSTR("ok"));
595 }
596 }
597
598 void precitaj_choreografiu_z_EEPROM(uint8_t slot)
599 {
600 uint8_t b3 = EEPROM.read(0);
601 uint8_t len1 = EEPROM.read(21);
602 uint8_t len2 = EEPROM.read(22);
603 uint8_t len3 = EEPROM.read(23);
604 uint16_t rp = 65535;
605 if ((len1 > CHOREO_LEN) || (len2 > CHOREO_LEN) || (len3 > CHOREO_LEN) || (b3 > 250 - len3) || ((len1 > b3) && (b3 != 0)) || (len3 + b3 > 250 - len2) || (len1 + len2 > 250))
606 b3 = len1 = len2 = len3 = 0;
607
608 if (slot == 1)
609 {
610 if (len1 > 0)
611 {
612 rp = 24;
613 ch_len = len1;
614 }
615 }
616 else if (slot == 2)
617 {
618 if (len2 > 0)
619 {
620 ch_len = len2;
621 rp = 1000 - ch_len * 4;
622 }
623 }
624 else if (slot == 3)
625 {
626 if (len3 > 0)
627 {
628 rp = b3 * 4;
629 ch_len = len3;
630 }
631 }
632
633 if (rp == 65535)
634 serial_println_flash(PSTR("couldn't"));
635 else
636 {
637 for (int i = 0; i < ch_len; i++)
638 {
639 ch_time[i] = ((uint16_t)EEPROM.read(rp + 4 * i)) |
640 (((uint16_t)EEPROM.read(rp + 1 + 4 * i)) << 8);
641 ch_servo[i] = EEPROM.read(rp + 2 + 4 * i);
642 ch_val[i] = EEPROM.read(rp + 3 + 4 * i);
643 }
644 serial_println_flash(PSTR("ok"));
645 pipni();
646 }
647 }
648
649 void naformatuj_EEPROM_choreografie()
650 {
651 EEPROM.write(0, 0);
652 EEPROM.write(21, 0);
653 EEPROM.write(22, 0);
654 EEPROM.write(23, 0);
655 serial_println_flash(PSTR("ok"));
656 pipni();
657 }
658
659 void precitaj_kalibraciu_z_EEPROM()
660 {
661 uint8_t value = EEPROM.read(1);
662 if (value != '~') return;
663 for (int i = 2; i < 8; i++)
664 prednastavena_kalibracia[i - 2] = EEPROM.read(i);
665 for (int i = 0; i < 6; i++)
666 dolny_limit[i] = EEPROM.read(i + 9);
667 for (int i = 0; i < 6; i++)
668 horny_limit[i] = EEPROM.read(i + 15);
669 }
670
671 char read_char()
672 {
673 while (!serial_available() && !Serial.available());
674 if (serial_available()) return serial_read();
675 else return Serial.read();
676 }
677
678 void zapis_kalibraciu_do_EEPROM()
679 {
680 serial_print_flash(PSTR("Naozaj chces zapisat kalibraciu do EEPROM? [Y/n]: "));
681 char odpoved = read_char();
682 serial_println_char(odpoved);
683 if (odpoved == 'Y')
684 {
685 EEPROM.write(1, '~');
686 for (int i = 2; i < 8; i++)
687 EEPROM.write(i, kalib[i - 2]);
688 for (int i = 0; i < 6; i++)
689 EEPROM.write(9 + i, dolny_limit[i]);
690 for (int i = 0; i < 6; i++)
691 EEPROM.write(15 + i, horny_limit[i]);
692 serial_println_flash(PSTR("ok"));
693 }
694 }
695
696 void pipni()
697 {
698 tone2( 1568, 50);
699 delay(100);
700 tone2( 1357, 50);
701 }
702
703 void ruky()
704 {
705 int odloz_krok = krok;
706 delay(500);
707 krok = 90;
708 pohyb(SERVO_LAVA_RUKA);
709 pohyb(SERVO_PRAVA_RUKA);
710 delay(1000);
711 krok = 180;
712 pohyb(-SERVO_LAVA_RUKA);
713 pohyb(-SERVO_PRAVA_RUKA);
714 delay(1000);
715 krok = odloz_krok;
716 pipni();
717 }
718
719 void ruky2()
720 {
721 int odloz_krok = krok;
722 delay(500);
723 krok = 180;
724 pohyb(SERVO_LAVA_RUKA);
725 pohyb(SERVO_PRAVA_RUKA);
726 delay(1000);
727 krok = 90;
728 pohyb(-SERVO_LAVA_RUKA);
729 pohyb(-SERVO_PRAVA_RUKA);
730 delay(1000);
731 krok = odloz_krok;
732 pipni();
733 }
734
735 void ahoj()
736 {
737 tone2( 1568, 50);
738 delay(70);
739 tone2( 1175, 30);
740 delay(50);
741 tone2( 880, 30);
742 delay(50);
743 tone2( 1047, 50);
744 delay(70);
745 tone2( 1245, 30);
746 delay(150);
747 tone2( 1568, 50);
748 delay(100);
749 if (random(10) > 4) tone2( 1357, 50);
750 else tone2( 1047, 50);
751 }
752
753 void nastav_koncatinu(int8_t servo, uint8_t poloha)
754 {
755 int8_t delta;
756 int8_t srv = (servo > 0)?servo:-servo;
757 srv--;
758 poloha += kalib[srv] - 90;
759 if (poloha > 180) poloha = 180;
760 if (poloha < 0) poloha = 0;
761
762 if (stav[srv] < poloha) delta = 1;
763 else delta = -1;
764 while (stav[srv] != poloha)
765 {
766 stav[srv] +=delta;
767 s[srv].write(stav[srv]);
768 delay(spomalenie);
769 }
770 }
771
772 void zobraz_stav()
773 {
774 for (int i = 0; i < 6; i++)
775 {
776 serial_print_flash(PSTR("S")); serial_print_num(i + 1); serial_print_flash(PSTR(": ")); serial_println_num(stav[i] - kalib[i] + 90);
777 }
778 serial_println_flash(PSTR("---"));
779 pipni();
780 }
781
782 void pohyb(int8_t servo)
783 {
784 int8_t srv = (servo > 0)?servo:-servo;
785 srv--;
786 if (servo_invertovane[srv]) servo = -servo;
787 if (servo > 0)
788 {
789 if (stav[srv] <= horny_limit[srv] - krok) stav[srv] += krok;
790 else stav[srv] = horny_limit[srv];
791 s[srv].write(stav[srv]);
792 }
793 else if (servo < 0)
794 {
795 if (stav[srv] >= dolny_limit[srv] + krok) stav[srv] -= krok;
796 else stav[srv] = dolny_limit[srv];
797 s[srv].write(stav[srv]);
798 }
799 }
800
801 uint8_t pohyb_znakom(char z)
802 {
803 for (int i = 0; i < 12; i++)
804 {
805 if (z == znaky_zmien[i])
806 {
807 int8_t servo = zmeny[i];
808 pohyb(servo);
809 }
810 }
811 }
812
813 void kombinacia1()
814 {
815 pohyb(SERVO_LAVA_NOHA);
816 pohyb(-SERVO_PRAVA_PATA);
817 }
818
819 void kombinacia2()
820 {
821 pohyb(SERVO_PRAVA_NOHA);
822 pohyb(-SERVO_LAVA_PATA);
823 }
824
825 void kombinacia3()
826 {
827 pohyb(SERVO_LAVA_RUKA);
828 pohyb(SERVO_PRAVA_RUKA);
829 }
830
831 void kombinacia4()
832 {
833 pohyb(-SERVO_LAVA_RUKA);
834 pohyb(-SERVO_PRAVA_RUKA);
835 }
836
837 int pohyb_kombinacia(char z)
838 {
839 if (z == '3') kombinacia1();
840 else if (z == '4') kombinacia2();
841 else if (z == '5') kombinacia3();
842 else if (z == '6') kombinacia4();
843 else return 0;
844 return 1;
845 }
846
847 int nacitajCislo()
848 {
849 int num = 0;
850 int z;
851 do {
852 z = read_char();
853 if (z == '#') while (z != 13) z = read_char();
854 } while ((z < '0') || (z > '9'));
855 while ((z >= '0') && (z <= '9'))
856 {
857 num *= 10;
858 num += (z - '0');
859 do { z = read_char(); if (z == -1) delayMicroseconds(10); } while (z < 0);
860 }
861 return num;
862 }
863
864 void nacitaj_choreografiu()
865 {
866 ch_len = 0;
867 int tm;
868 do {
869 tm = nacitajCislo();
870 ch_time[ch_len] = tm;
871 ch_servo[ch_len] = nacitajCislo();
872 ch_val[ch_len] = nacitajCislo();
873 ch_len++;
874 if (ch_len == CHOREO_LEN) break;
875 } while (tm > 0);
876 pipni();
877 }
878
879 void vypis_choreografiu()
880 {
881 for (int i = 0; i < ch_len; i++)
882 {
883 serial_print_num(ch_time[i]);
884 serial_print(" ");
885 serial_print_num(ch_servo[i]);
886 serial_print(" ");
887 serial_println_num(ch_val[i]);
888 }
889 serial_println_flash(PSTR("---"));
890 pipni();
891 }
892
893 void zatancuj_choreografiu(uint16_t *ch_time, uint8_t *ch_servo, uint8_t *ch_val, int ch_len )
894 {
895 for (int i = 0; i < ch_len - 1; i++)
896 {
897 delay(ch_time[i]);
898 if (ch_servo[i] < 9) nastav_koncatinu(ch_servo[i], ch_val[i]);
899 else i = specialny_prikaz(ch_servo[i], ch_val[i]);
900 if (serial_available() || Serial.available()) break;
901 }
902 pipni();
903 while (serial_available()) serial_read();
904 while (Serial.available()) Serial.read();
905 }
906
907 int specialny_prikaz(uint8_t prikaz, uint8_t argument)
908 {
909 if (prikaz == 9) return ((int)argument) - 1;
910 else if (prikaz == 10) spomalenie = argument;
911 else if (prikaz == 11) zacni_hrat_melodiu(argument);
912 else if (prikaz == 12) zvukovy_efekt(argument);
913 }
914
915 void zacni_hrat_melodiu(uint8_t cislo)
916 {
917
918 }
919
920 void reset()
921 {
922 for (int i = 0; i < 6; i++)
923 {
924 stav[i] = kalib[i];
925 s[i].write(kalib[i]);
926 delay(300);
927 }
928 pipni();
929 }
930
931 uint8_t nalad_hodnotu_serva(uint8_t servo, uint8_t hodnota)
932 {
933 serial_print_flash(PSTR(" (+/-/ENTER): "));
934 serial_println_num(hodnota);
935 s[servo].write(hodnota);
936 char z;
937 do {
938 z = read_char();
939 if ((z == '+') && (hodnota < 180)) hodnota++;
940 else if ((z == '-') && (hodnota > 0)) hodnota--;
941 if ((z == '+') || (z == '-'))
942 {
943 serial_print_num(hodnota); serial_print_char('\r');
944 s[servo].write(hodnota);
945 }
946 } while (z != 13);
947 return hodnota;
948 }
949
950 void kalibruj()
951 {
952 for (int i = 0; i < 6; i++)
953 {
954 serial_print_num(i);
955 kalib[i] = nalad_hodnotu_serva(i, kalib[i]);
956 serial_print_num(i);
957 serial_print(": ");
958 serial_println_num(kalib[i]);
959 }
960 for (int i = 0; i < 6; i++) { serial_print_num(kalib[i]); serial_print(" "); }
961 serial_println_flash(PSTR("ok"));
962 pipni();
963 }
964
965 void nastav_limity()
966 {
967 for (int i = 0; i < 6; i++)
968 {
969 serial_print_num(i);
970 serial_print_flash(PSTR("dolny"));
971 dolny_limit[i] = nalad_hodnotu_serva(i, dolny_limit[i]);
972 serial_print_num(i);
973 serial_print_flash(PSTR(" dolny: "));
974 serial_println_num(dolny_limit[i]);
975 s[i].write(kalib[i]);
976
977 serial_print_num(i);
978 serial_print_flash(PSTR("horny"));
979 horny_limit[i] = nalad_hodnotu_serva(i, horny_limit[i]);
980 serial_print_num(i);
981 serial_print_flash(PSTR(" horny: "));
982 serial_println_num(horny_limit[i]);
983 s[i].write(kalib[i]);
984 }
985 for (int i = 0; i < 6; i++) { serial_print_num(dolny_limit[i]); serial_print("-"); serial_print_num(horny_limit[i]); serial_print(" "); }
986 serial_println_flash(PSTR("ok"));
987 pipni();
988 }
989
990 void vypis_kalibraciu()
991 {
992 serial_print_flash(PSTR("stredy: "));
993 for (int i = 0; i < 6; i++) { serial_print_num(kalib[i]); serial_print(" "); }
994 serial_println();
995 serial_print_flash(PSTR("dolny limit: "));
996 for (int i = 0; i < 6; i++) { serial_print_num(dolny_limit[i]); serial_print(" "); }
997 serial_println();
998 serial_print_flash(PSTR("horny limit: "));
999 for (int i = 0; i < 6; i++) { serial_print_num(horny_limit[i]); serial_print(" "); }
1000 serial_println();
1001 }
1002
1003 void nacitaj_kalibraciu()
1004 {
1005 int tm;
1006 for (int i = 0; i < 6; i++)
1007 kalib[i] = nacitajCislo();
1008 vypis_kalibraciu();
1009 serial_println_flash(PSTR("ok"));
1010 pipni();
1011 }
1012
1013 void zvys_krok()
1014 {
1015 if (krok < 180) krok++;
1016 serial_print_flash(PSTR("krok: "));
1017 serial_println_num(krok);
1018 }
1019
1020 void zniz_krok()
1021 {
1022 if (krok > 0) krok--;
1023 serial_print_flash(PSTR("krok: "));
1024 serial_println_num(krok);
1025 }
1026
1027 void zniz_spomalenie()
1028 {
1029 if (spomalenie > 0) spomalenie--;
1030 serial_print_flash(PSTR("spomalenie: "));
1031 serial_println_num(spomalenie);
1032 }
1033
1034 void zvys_spomalenie()
1035 {
1036 if (spomalenie < 100) spomalenie++;
1037 serial_print_flash(PSTR("spomalenie: "));
1038 serial_println_num(spomalenie);
1039 }
1040
1041 // nasleduje softverova implementacia serioveho portu
1042 #define SERIAL_STATE_IDLE 0
1043 #define SERIAL_STATE_RECEIVING 1
1044 #define SERIAL_BUFFER_LENGTH 20
1045
1046 static volatile uint8_t serial_state;
1047 static uint8_t serial_buffer[SERIAL_BUFFER_LENGTH];
1048 static volatile uint8_t serial_buf_wp, serial_buf_rp;
1049
1050 static volatile uint8_t receiving_byte;
1051
1052 static volatile uint32_t time_startbit_noticed;
1053 static volatile uint8_t next_bit_order;
1054 static volatile uint8_t waiting_stop_bit;
1055 static uint16_t one_byte_duration;
1056 static uint16_t one_bit_duration;
1057 static uint16_t one_bit_write_duration;
1058 static uint16_t half_of_one_bit_duration;
1059
1060 void init_serial(uint32_t baud_rate)
1061 {
1062 pinMode(2, INPUT);
1063 pinMode(4, OUTPUT);
1064
1065 serial_state = SERIAL_STATE_IDLE;
1066
1067 one_byte_duration = 9500000 / baud_rate;
1068 one_bit_duration = 1000000 / baud_rate;
1069 one_bit_write_duration = one_bit_duration - 1;
1070 half_of_one_bit_duration = 500000 / baud_rate;
1071
1072 PCMSK2 |= 4; //PCINT18;
1073 PCIFR &= ~4; //PCIF2;
1074 PCICR |= 4; // PCIE2;
1075 }
1076
1077 ISR(PCINT2_vect)
1078 {
1079 uint32_t tm = micros();
1080 if (serial_state == SERIAL_STATE_IDLE)
1081 {
1082 time_startbit_noticed = tm;
1083 serial_state = SERIAL_STATE_RECEIVING;
1084 receiving_byte = 0xFF;
1085 next_bit_order = 0;
1086 }
1087 else if (tm - time_startbit_noticed > one_byte_duration)
1088 {
1089 serial_buffer[serial_buf_wp] = receiving_byte;
1090 serial_buf_wp++;
1091 if (serial_buf_wp == SERIAL_BUFFER_LENGTH) serial_buf_wp = 0;
1092 time_startbit_noticed = tm;
1093 receiving_byte = 0xFF;
1094 next_bit_order = 0;
1095 }
1096 else if (PIND & 4)
1097 {
1098 int8_t new_next_bit_order = (tm - time_startbit_noticed - half_of_one_bit_duration) / one_bit_duration;
1099 while (next_bit_order < new_next_bit_order)
1100 {
1101 receiving_byte &= ~(1 << next_bit_order);
1102 next_bit_order++;
1103 }
1104 if (next_bit_order == 8)
1105 {
1106 serial_buffer[serial_buf_wp] = receiving_byte;
1107 serial_buf_wp++;
1108 if (serial_buf_wp == SERIAL_BUFFER_LENGTH) serial_buf_wp = 0;
1109 serial_state = SERIAL_STATE_IDLE;
1110 }
1111 } else
1112 next_bit_order = (tm - time_startbit_noticed - half_of_one_bit_duration) / one_bit_duration;
1113 }
1114
1115 uint8_t serial_available()
1116 {
1117 cli();
1118 if (serial_buf_rp != serial_buf_wp)
1119 {
1120 sei();
1121 return 1;
1122 }
1123 if (serial_state == SERIAL_STATE_RECEIVING)
1124 {
1125 uint32_t tm = micros();
1126 if (tm - time_startbit_noticed > one_byte_duration)
1127 {
1128 serial_state = SERIAL_STATE_IDLE;
1129 serial_buffer[serial_buf_wp] = receiving_byte;
1130 serial_buf_wp++;
1131 if (serial_buf_wp == SERIAL_BUFFER_LENGTH) serial_buf_wp = 0;
1132 sei();
1133 return 1;
1134 }
1135 }
1136 sei();
1137 return 0;
1138 }
1139
1140 int16_t serial_read()
1141 {
1142 cli();
1143 if (serial_buf_rp != serial_buf_wp)
1144 {
1145 uint8_t ch = serial_buffer[serial_buf_rp];
1146 serial_buf_rp++;
1147 if (serial_buf_rp == SERIAL_BUFFER_LENGTH) serial_buf_rp = 0;
1148 sei();
1149 return ch;
1150 }
1151
1152 if (serial_state == SERIAL_STATE_RECEIVING)
1153 {
1154 uint32_t tm = micros();
1155 if (tm - time_startbit_noticed > one_byte_duration)
1156 {
1157 uint8_t ch = receiving_byte;
1158 serial_state = SERIAL_STATE_IDLE;
1159 sei();
1160 return ch;
1161 }
1162 }
1163 sei();
1164 return -1;
1165 }
1166
1167 void serial_write(uint8_t ch)
1168 {
1169 #ifdef ECHO_BT_TO_USB
1170 Serial.print((char)ch);
1171 #endif
1172 PORTD &= ~16;
1173 delayMicroseconds(one_bit_write_duration);
1174 for (uint8_t i = 0; i < 8; i++)
1175 {
1176 if (ch & 1) PORTD |= 16;
1177 else PORTD &= ~16;
1178 ch >>= 1;
1179 delayMicroseconds(one_bit_write_duration);
1180 }
1181 PORTD |= 16;
1182 delayMicroseconds(one_bit_write_duration);
1183 delayMicroseconds(one_bit_write_duration);
1184 delayMicroseconds(one_bit_write_duration);
1185 delayMicroseconds(one_bit_write_duration);
1186 delayMicroseconds(one_bit_write_duration);
1187 }
1188
1189 uint16_t serial_readln(uint8_t *ln, uint16_t max_length)
1190 {
1191 uint16_t len;
1192 uint16_t ch;
1193 do {
1194 ch = serial_read();
1195 if (ch == 13) continue;
1196 } while (ch == -1);
1197
1198 do {
1199 if ((ch != 13) && (ch != 10) && (ch != -1))
1200 {
1201 *(ln++) = ch;
1202 max_length--;
1203 len++;
1204 }
1205 ch = serial_read();
1206 } while ((ch != 13) && max_length);
1207 *ln = 0;
1208 return len;
1209 }
1210
1211 void serial_print_num(int32_t number)
1212 {
1213 if (number < 0)
1214 {
1215 serial_write('-');
1216 number = -number;
1217 }
1218 int32_t rad = 1;
1219 while (number / rad) rad *= 10;
1220 if (number > 0) rad /= 10;
1221 while (rad)
1222 {
1223 serial_write((char)('0' + (number / rad)));
1224 number -= (number / rad) * rad;
1225 rad /= 10;
1226 }
1227 }
1228
1229 void serial_print_char(char ch)
1230 {
1231 serial_write(ch);
1232 }
1233
1234 void serial_print(const uint8_t *str)
1235 {
1236 while (*str) serial_write(*(str++));
1237 }
1238
1239 void serial_println(const uint8_t *str)
1240 {
1241 serial_print(str);
1242 serial_write(13);
1243 serial_write(10);
1244 }
1245
1246 void serial_print_flash(const uint8_t PROGMEM *str)
1247 {
1248 int ln = strlen_P(str);
1249 for (int i = 0; i < ln; i++)
1250 serial_write(pgm_read_byte(str + i));
1251 }
1252
1253 void serial_println_flash(const uint8_t PROGMEM *str)
1254 {
1255 serial_print_flash(str);
1256 serial_write(13);
1257 serial_write(10);
1258 }
1259
1260 void serial_println_num(int32_t number)
1261 {
1262 serial_print_num(number);
1263 serial_println();
1264 }
1265
1266 void serial_println_char(char ch)
1267 {
1268 serial_write(ch);
1269 serial_println();
1270 }
1271
1272 void serial_println()
1273 {
1274 serial_write(13);
1275 serial_write(10);
1276 }
1277
1278 // nasleduje citanie z utltazvukoveho senzora
1279
1280 static volatile uint32_t pulse_start;
1281 static volatile uint8_t new_distance;
1282
1283 void init_ultrasonic()
1284 {
1285 pinMode(US_ECHO, INPUT);
1286 pinMode(US_TRIG, OUTPUT);
1287
1288 PCMSK0 |= 1; //PCINT0;
1289 PCIFR &= ~1; //PCIF0;
1290 PCICR |= 1; // PCIE0;
1291 }
1292
1293 ISR(PCINT0_vect)
1294 {
1295 if (PINB & 1) pulse_start = micros();
1296 else
1297 {
1298 distance = (int16_t)((micros() - pulse_start) / 58);
1299 new_distance = 1;
1300 }
1301 }
1302
1303 void start_distance_measurement()
1304 {
1305 distance = 10000;
1306 new_distance = 0;
1307 digitalWrite(US_TRIG, HIGH);
1308 delayMicroseconds(10);
1309 digitalWrite(US_TRIG, LOW);
1310 }
1311
1312 void wait_for_distance_measurement_to_complete()
1313 {
1314 uint8_t counter = 0;
1315 while ((counter < 20) && !new_distance)
1316 {
1317 delay(1);
1318 counter++;
1319 }
1320 if (counter == 20)
1321 {
1322 pinMode(US_ECHO, OUTPUT);
1323 digitalWrite(US_ECHO, HIGH);
1324 delayMicroseconds(10);
1325 digitalWrite(US_ECHO, LOW);
1326 pinMode(US_ECHO, INPUT);
1327 delayMicroseconds(5);
1328 distance = 10000;
1329 }
1330 }
1331
1332 int16_t measure_distance()
1333 {
1334 start_distance_measurement();
1335 wait_for_distance_measurement_to_complete();
1336 return distance;
1337 }
1338
1339 //-------------------------------- nasleduje prehravanie melodie a hranie cez timer2 v pozadi
1340 #define SIRENE_PORT PORTB
1341 #define SIRENE_DDR DDRB
1342 #define SIRENE_PIN 4
1343
1344 #define FIS3 2960
1345 #define G3 3136
1346
1347 float octave_4[] = { 2093.00, 2217.46, 2349.32, 2489.02, 2637.02, 2793.83, 2959.96, 3135.96, 3322.44, 3520.00, 3729.31, 3951.07 };
1348
1349 //popcorn
1350 uint16_t dlzka_melodia[] = {0, 386, 26, 281, 217};
1351 const uint8_t melodia1[] PROGMEM = { 252, 50, 149, 49,
1352 28, 31, 35, 40, 49, 99, 38, 49, 99, 40, 49, 99, 35, 49, 99, 31, 49, 99, 35, 49, 99, 28, 49, 99, 49,
1353 28, 31, 35, 40, 49, 99, 38, 49, 99, 40, 49, 99, 35, 49, 99, 31, 49, 99, 35, 49, 99, 28, 49, 99, 149,
1354 40, 49, 99, 42, 49, 99, 43, 49, 99, 42, 49, 99, 43, 49, 99, 40, 49, 99, 42, 49, 99, 40, 49, 99, 42, 49, 99, 38, 49, 99, 40, 49, 99, 38, 49, 99, 40, 49, 99, 36, 49, 99, 40, 49, 99,
1355 28, 31, 35, 40, 49, 99, 38, 49, 99, 40, 49, 99, 35, 49, 99, 31, 49, 99, 35, 49, 99, 28, 49, 99, 49,
1356 28, 31, 35, 40, 49, 99, 38, 49, 99, 40, 49, 99, 35, 49, 99, 31, 49, 99, 35, 49, 99, 28, 49, 99, 149,
1357 40, 49, 99, 42, 49, 99, 43, 49, 99, 42, 49, 99, 43, 49, 99, 40, 49, 99, 42, 49, 99, 40, 49, 99, 42, 49, 99, 38, 49, 99, 40, 49, 99, 38, 49, 99, 40, 49, 99, 42, 49, 99, 43, 49, 99,
1358 49, 35, 38, 43, 47, 49, 99, 45, 49, 99, 47, 49, 99, 43, 49, 99, 38, 49, 99, 43, 49, 99, 35, 49, 99,
1359 49, 35, 38, 43, 47, 49, 99, 45, 49, 99, 47, 49, 99, 43, 49, 99, 38, 49, 99, 43, 49, 99, 35, 49, 99, 149 ,
1360 47, 49, 99, 254, 49, 99, 255, 49, 99, 254, 49, 99, 255, 49, 99, 47, 49, 99, 254, 49, 99, 47, 49, 99, 254, 49, 99, 45, 49, 99, 47, 49, 99, 45, 49, 99, 47, 49, 99, 43, 49, 99, 47, 49, 99,
1361 49, 35, 38, 43, 47, 49, 99, 45, 49, 99, 47, 49, 99, 43, 49, 99, 38, 49, 99, 43, 49, 99, 35, 49, 99,
1362 49, 35, 38, 43, 47, 49, 99, 45, 49, 99, 47, 49, 99, 43, 49, 99, 38, 49, 99, 43, 49, 99, 35, 49, 99, 149 ,
1363 47, 49, 99, 254, 49, 99, 255, 49, 99, 254, 49, 99, 255, 49, 99, 47, 49, 99, 254, 49, 99, 47, 49, 99, 254, 49, 99, 45, 49, 99, 47, 49, 99, 45, 49, 99, 47, 49, 99, 254, 49, 99, 255, 49, 99
1364 };
1365
1366 //kohutik jarabi
1367 const uint8_t melodia2[] PROGMEM = { 252, 150, 119, 121, 173, 174, 124, 124, 124, 123, 171, 173, 123, 123, 123, 121, 169, 171, 121, 121, 121, 123, 171, 169, 119, 119 };
1368
1369 // kankán
1370 const uint8_t melodia3[] PROGMEM = { 252, 100,
1371 251,1,184,1,32,126,149,251,1,184,1,32,126,149,251,1,184,1,32,126,251,1,184,1,32,126,251,1,184,1,32,126,251,1,184,1,32,126,
1372 64,71,71,73,71,69,69,73,74,78,81,78,78,76,251,1,184,1,32,126,78,68,68,78,76,69,69,73,73,71,73,71,85,83,85,83,
1373 64,71,71,73,71,69,69,73,74,78,81,78,78,76,251,1,184,1,32,126,78,68,68,78,76,69,69,73,73,71,73,71,71,69,119,
1374 135,131,128,126,75,76,78,80,81,76,80,76,81,76,80,76,81,76,80,76,81,76,80,76,
1375 251,2,11,3,16,19,251,1,4,3,16,19,
1376 251,1,4,3,16,19,251,1,4,3,16,19,
1377 251,1,4,3,16,19,251,1,4,3,16,19,
1378 251,1,4,3,16,19,251,1,4,3,16,19,
1379 174,88,91,90,88,143,143,93,95,90,91,138,138,88,91,90,88,86,86,85,83,81,79,78,76,
1380 174,88,91,90,88,143,143,93,95,90,91,138,138,88,91,90,88,86,93,89,90,136,
1381 64,71,71,73,71,69,69,73,74,78,81,78,78,76,251,1,184,1,32,126,
1382 78,76,126,78,76,126,78,76,126,78,76,126,78,76,126,78,76,126,
1383 78,76,78,76,78,76,78,76,
1384 131,119,119,119,169 };
1385
1386 //labutie jazero
1387 const uint8_t melodia4[] PROGMEM = {
1388 252, 220, 66, 69, 73, 69, 66, 69, 73, 69, 66, 69, 73, 69, 66, 69, 73, 69,
1389 185, 78, 80, 81, 83, 251, 5, 39, 3, 8, 81, 251, 5, 39, 3, 8, 81, 251, 5, 39, 3, 8, 78, 81, 78, 73, 81, 178,
1390 99, 83, 81, 80,
1391 185, 78, 80, 81, 83, 251, 5, 39, 3, 8, 81, 251, 5, 39, 3, 8, 81, 251, 5, 39, 3, 8, 78, 81, 78, 73, 81, 178,
1392 149, 128, 130, 131, 133, 85, 86, 251, 6, 32, 3, 8, 86, 135, 86, 88, 251, 6, 224, 3, 8, 88, 136, 88, 90, 251, 7, 184, 3, 8, 90, 85, 81, 80, 78,
1393 130, 131, 133, 85, 86, 251, 6, 32, 3, 8, 86, 135, 86, 88, 251, 6, 224, 3, 8, 88, 136, 88, 90, 251, 7, 73, 3, 8, 86, 133, 86, 91, 251, 7, 184, 3, 8, 87, 251, 7, 184, 3, 8, 85,
1394 185, 78, 80, 81, 83, 251, 5, 39, 3, 8, 81, 251, 5, 39, 3, 8, 81, 251, 5, 39, 3, 8, 78, 81, 78, 73, 81, 178,
1395 99, 83, 81, 80,
1396 185, 78, 80, 81, 83, 251, 5, 39, 3, 8, 81, 251, 5, 39, 3, 8, 81, 251, 5, 39, 3, 8, 78, 81, 78, 73, 81, 178 };
1397
1398 volatile int16_t music_speed = 800 / 16;
1399
1400 volatile PGM_P current_note ;
1401 volatile uint16_t notes_remaining;
1402
1403 void zahraj_melodiu(uint8_t cislo)
1404 {
1405 if (cislo == 1) current_note = melodia1;
1406 else if (cislo == 2) current_note = melodia2;
1407 else if (cislo == 3) current_note = melodia3;
1408 else if (cislo == 4) current_note = melodia4;
1409 notes_remaining = dlzka_melodia[cislo];
1410
1411 next_note();
1412 }
1413
1414 void next_note()
1415 {
1416 uint16_t freq, dur;
1417 if (!notes_remaining) return;
1418 otto_translate_tone_flash(&freq, &dur);
1419 tone2(freq, dur);
1420 }
1421
1422 void otto_translate_tone_flash(uint16_t *freq, uint16_t *del)
1423 {
1424 do {
1425 uint8_t n = pgm_read_byte(current_note);
1426 if (n == 251)
1427 {
1428 current_note++;
1429 uint8_t f1 = pgm_read_byte(current_note);
1430 current_note++;
1431 uint8_t f2 = pgm_read_byte(current_note);
1432 current_note++;
1433 uint8_t d1 = pgm_read_byte(current_note);
1434 current_note++;
1435 uint8_t d2 = pgm_read_byte(current_note);
1436 *freq = (f1 << 8) + f2;
1437 *del = (music_speed * 16 * (long)d1) / d2;
1438 notes_remaining -= 4;
1439 }
1440 else if (n == 252)
1441 {
1442 current_note++;
1443 music_speed = pgm_read_byte(current_note);
1444 current_note++;
1445 notes_remaining -= 2;
1446 continue;
1447 }
1448 else if (n == 254)
1449 {
1450 *freq = FIS3;
1451 *del = music_speed;
1452 }
1453 else if (n == 255)
1454 {
1455 *freq = G3;
1456 *del = music_speed;
1457 }
1458 else
1459 {
1460 uint8_t len = n / 50;
1461 *del = music_speed;
1462 while (len--) *del *= 2;
1463 n = n % 50;
1464 if (n != 49)
1465 {
1466 uint8_t octave = (n + 5) / 12;
1467 n = (n + 5) % 12;
1468 float ffreq = octave_4[n];
1469 octave = 4 - octave;
1470 while (octave > 0)
1471 {
1472 ffreq /= 2.0;
1473 octave--;
1474 }
1475 *freq = (uint16_t)ffreq;
1476 }
1477 else *freq = 0;
1478 }
1479 notes_remaining--;
1480 current_note++;
1481 break;
1482 } while(1);
1483 }
1484
1485 static volatile uint8_t tone2_state;
1486 static volatile uint8_t tone2_pause;
1487 static volatile uint32_t tone2_len;
1488
1489 void init_tone2()
1490 {
1491 notes_remaining = 0;
1492 tone2_pause = 0;
1493 TCCR2A = 2;
1494 TCCR2B = 0;
1495 TIMSK2 = 2;
1496 SIRENE_DDR |= (1 << SIRENE_PIN);
1497 }
1498
1499
1500 ISR(TIMER2_COMPA_vect)
1501 {
1502 if (!tone2_pause)
1503 {
1504 if (tone2_state)
1505 {
1506 SIRENE_PORT |= (1 << SIRENE_PIN);
1507 tone2_state = 0;
1508 }
1509 else
1510 {
1511 SIRENE_PORT &= ~(1 << SIRENE_PIN);
1512 tone2_state = 1;
1513 }
1514 }
1515 if ((--tone2_len) == 0)
1516 {
1517 TCCR2B = 0;
1518 tone2_pause = 0;
1519 next_note();
1520 }
1521 }
1522
1523 void tone2(uint16_t freq, uint16_t duration)
1524 {
1525 uint32_t period = ((uint32_t)1000000) / (uint32_t)freq;
1526
1527 if (freq >= 977) // prescaler 32
1528 {
1529 tone2_state = 0;
1530 tone2_len = ((uint32_t)duration * (uint32_t)1000) * 2 / period;
1531 if (tone2_len == 0) tone2_len++;
1532 TCNT2 = 0;
1533 OCR2A = (uint8_t) (250000 / (uint32_t)freq);
1534 TCCR2B = 3;
1535 }
1536 else if (freq >= 488) // prescaler 64
1537 {
1538 tone2_state = 0;
1539 tone2_len = ((uint32_t)duration * (uint32_t)1000) * 2 / period;
1540 if (tone2_len == 0) tone2_len++;
1541 TCNT2 = 0;
1542 OCR2A = (uint8_t) (125000 / (uint32_t)freq);
1543 TCCR2B = 4;
1544 }
1545 else if (freq >= 244) // prescaler 128
1546 {
1547 tone2_state = 0;
1548 tone2_len = ((uint32_t)duration * (uint32_t)1000) * 2 / period;
1549 if (tone2_len == 0) tone2_len++;
1550 TCNT2 = 0;
1551 OCR2A = (uint8_t) (62500 / (uint32_t)freq);
1552 TCCR2B = 5;
1553 }
1554 else if (freq >= 122) //prescaler 256
1555 {
1556 tone2_state = 0;
1557 tone2_len = ((uint32_t)duration * (uint32_t)1000) * 2 / period;
1558 if (tone2_len == 0) tone2_len++;
1559 TCNT2 = 0;
1560 OCR2A = (uint8_t) (31250 / (uint32_t)freq);
1561 TCCR2B = 6;
1562 }
1563 else if (freq >= 30) //prescaler 1024
1564 {
1565 tone2_state = 0;
1566 tone2_len = ((uint32_t)duration * (uint32_t)1000) * 2 / period;
1567 if (tone2_len == 0) tone2_len++;
1568 TCNT2 = 0;
1569 OCR2A = (uint8_t) (7813 / (uint32_t)freq);
1570 TCCR2B = 7;
1571 }
1572 else if (freq == 0)
1573 {
1574 tone2_pause = 1;
1575 tone2_state = 0;
1576 period = 1000000 / 500;
1577 tone2_len = ((uint32_t)duration * (uint32_t)1000) * 2 / period;
1578 TCNT2 = 0;
1579 OCR2A = (uint8_t) (125000 / (uint32_t)500);
1580 TCCR2B = 4;
1581 }
1582 else
1583 {
1584 TCCR2B = 0;
1585 }
1586 }