Hauptprojekt.ino 25 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802
  1. //Verfassser: Felix Stange, 4056379, MET2016
  2. //Datum: erstellt am 19.07.2017, zuletzt geändert am 17.05.2018
  3. //Projektthema: Untersuchungen und Implementierung eines automatisierten Fahrens mittels Pololu Zumo
  4. /*Kurzbeschreibung: Der Zumo fährt automatisch zwischen 2 Linien ohne diese zu überfahren mithilfe
  5. der Liniensensoren (3), ähnlich einer Spurhalteautomatik (heller Belag und dunkle Streifen).
  6. Außerdem werden Kollisionen verhindert durch Nutzung der vorderen Abstandssensoren. Kommt es
  7. dennoch zu einer Kollision, wird diese durch den Beschleunigungssensor (LSM303) erkannt.
  8. Für den Überholvorgang werden die seitlichen Abstandssensoren und der Drehbewegungssensor (L3G)
  9. genutzt. Mithilfe der Quadraturencoder in den Motoren können Wegstrecken vermessen werden.
  10. Für die Filterung der Messwerte werden Medianfilter genutzt. Der Zumo kommuniziert über ein
  11. Bluetooth-Modul (HC-05) mit anderen Geräten. Die Kommunikation erfolgt seriell ('SERIAL' für USB,
  12. 'SERIAL1' für Bluetooth). Das LCD kann bei Bluetoothnutzung nicht verwendet werden.*/
  13. #include <Wire.h>
  14. #include <Zumo32U4.h>
  15. #include <MedianFilter.h>
  16. Zumo32U4ProximitySensors proxSensors; //Abstandssensoren
  17. Zumo32U4LineSensors lineSensors; //Liniensensoren
  18. Zumo32U4Motors motors; //Motoren
  19. Zumo32U4ButtonA buttonA; //Taste A
  20. Zumo32U4Encoders encoders; //Motorencoder
  21. LSM303 compass; //Beschleunigungssensor x-Achse
  22. L3G gyro; //Drehbewegungssensor z-Achse
  23. //Medianfilter geben mittleren Wert einer Reihe mit ungerader Anzahl aus
  24. MedianFilter LineFilter0(3, 0); //erstellen der Filter für Liniensensoren
  25. MedianFilter LineFilter1(3, 0); //Fenstergröße: 3, Basiswerte: 0 0 0
  26. MedianFilter LineFilter2(3, 0);
  27. MedianFilter ProxFilter0(5, 0); //erstellen der Filter für Abstandssensoren
  28. MedianFilter ProxFilter1(5, 0); //Fenstergröße: 5, Basiswerte: 0 0 0 0 0
  29. MedianFilter ProxFilter2(5, 0);
  30. MedianFilter ProxFilter3(5, 0);
  31. #define MARKLINE0 150
  32. #define MARKLINE1 100
  33. #define MARKLINE2 120
  34. #define SIGN0 500
  35. #define SIGN1 300
  36. #define SIGN2 500
  37. #define MAXSPEED 400
  38. #define FULLSPEEDLEFT 104
  39. #define HALFSPEEDLEFT 52
  40. #define SLOWSPEEDLEFT 26
  41. #define FULLSPEEDRIGHT 100
  42. #define HALFSPEEDRIGHT 50
  43. #define SLOWSPEEDRIGHT 25
  44. int16_t lineValue[3]; //Liniensensoren
  45. uint16_t lineOffset[3]; //von links (0) nach rechts (2)
  46. uint8_t proxValue[4]; //Abstandssensoren v.l. (0) n.r. (3)
  47. int16_t encoderCounts[2]; //Anzahl der Umdrehungen
  48. int16_t driveRotation[2]; //von links (0) nach rechts (1)
  49. int32_t rotationAngle = 0; //Drehwinkel
  50. int32_t turnAngle = 0;
  51. int16_t turnRate;
  52. int16_t gyroOffset;
  53. uint16_t gyroLastUpdate;
  54. int16_t compassRate; //Beschleunigung
  55. int16_t compassOffset;
  56. int16_t compassLastUpdate;
  57. uint16_t lastUpdate = 0; //Systemzeit
  58. uint16_t eventTime = 0; //Zeitdifferenz
  59. uint16_t stopUpdate = 0; //Systemzeit
  60. uint16_t stopTime = 0; //Zeit seit letztem Manöver
  61. float eventSpeed = 1; //vermindert die Geschwindigkeit bei Manövern
  62. int btData = 0; //Gelesene Daten aus Bluetooth
  63. bool btBuffer = false; //puffert Daten von btData
  64. bool stop = false; //Sperrt Funktion Kontaktvermeiden
  65. /*-----------------------------------------------------------------*/
  66. //Setup Bluetoothverbindung
  67. void BlueSetup()
  68. {
  69. Serial1.begin(9600); //Initialisierung mit Datengeschwindigkeit(Baud)
  70. Serial1.setTimeout(10); //verkürzt Serial(1).read auf 10 ms statt 1000 ms
  71. if(Serial1.available()) Serial.println("Bluetoothverbindung hergestellt");
  72. if(Serial1.available() > 0) Serial1.read(); //Verwerfen der alten Informationen aus dem Puffer
  73. Serial1.print(0);
  74. }
  75. //Setup Liniensensoren
  76. void LineSetup()
  77. {
  78. ledYellow(1);
  79. lineSensors.initThreeSensors(); //Initialisierung von 3 Sensoren (max 5)
  80. //Kalibrierung
  81. uint32_t total[3] = {0, 0, 0};
  82. for(uint8_t i = 0; i < 120; i++)
  83. {
  84. if (i > 30 && i <= 90) motors.setSpeeds(FULLSPEEDLEFT, -FULLSPEEDRIGHT);
  85. else motors.setSpeeds(-FULLSPEEDLEFT, FULLSPEEDRIGHT);
  86. lineSensors.read(lineOffset);
  87. total[0] += lineOffset[0];
  88. total[1] += lineOffset[1];
  89. total[2] += lineOffset[2];
  90. lineSensors.calibrate();
  91. }
  92. motors.setSpeeds(0, 0);
  93. lineOffset[0] = total[0] / 120;
  94. lineOffset[1] = total[1] / 120;
  95. lineOffset[2] = total[2] / 120;
  96. ledYellow(0);
  97. // lineOffset[0] = 240;
  98. // lineOffset[1] = 120;
  99. // lineOffset[2] = 220;
  100. }
  101. //Setup Abstandssensoren
  102. void ProxSetup()
  103. {
  104. proxSensors.initThreeSensors();
  105. }
  106. //Setup Drehbewegungssensor
  107. void GyroSetup()
  108. {
  109. ledYellow(1);
  110. gyro.init(); //Initialisierung
  111. if(!gyro.init()) //Fehlerabfrage
  112. {
  113. //Fehler beim Initialisieren des Drehbewegungssensors
  114. ledRed(1);
  115. while(1)
  116. {
  117. Serial.println("Fehler Drehbewegungssensors");
  118. delay(5000);
  119. }
  120. }
  121. gyro.writeReg(L3G::CTRL1, 0b11111111); //Ausgaberate 800Hz, Tiefpassfilter 100Hz
  122. gyro.writeReg(L3G::CTRL4, 0b00100000); //2000dps Auflösung
  123. gyro.writeReg(L3G::CTRL5, 0b00000000); //Hochpassfilter ausgeschaltet
  124. //Kalibrierung
  125. int32_t total = 0;
  126. for(uint16_t i = 0; i < 1024; i++)
  127. {
  128. while(!gyro.readReg(L3G::STATUS_REG) & 0x08); //Fehlerabfrage
  129. gyro.read();
  130. total += gyro.g.z;
  131. }
  132. gyroOffset = total / 1024;
  133. gyroLastUpdate = micros();
  134. ledYellow(0);
  135. }
  136. //Setup Beschleunigungssensor
  137. void CompassSetup()
  138. {
  139. ledYellow(1);
  140. compass.init(); //Initialisierung
  141. if(!compass.init()) //Fehlerabfrage
  142. {
  143. //Fehler beim Initialisieren des Beschleunigungssensors
  144. ledRed(1);
  145. while(1)
  146. {
  147. Serial.println("Fehler Beschleunigungssensors");
  148. delay(5000);
  149. }
  150. }
  151. compass.enableDefault();
  152. //Kalibrierung
  153. int32_t total = 0;
  154. for (uint16_t i = 0; i < 1024; i++)
  155. {
  156. compass.readAcc();
  157. total += compass.a.x;
  158. }
  159. compassOffset = total / 1024;
  160. //compassLastUpdate = micros();
  161. ledYellow(0);
  162. }
  163. /*-----------------------------------------------------------------*/
  164. void setup()
  165. {
  166. //Initialisierung der Bluetoothverbindung
  167. BlueSetup();
  168. //Initialisierung und Kalibrierung der Sensoren
  169. //Serial1.println("Sensorkalibrierung");
  170. Wire.begin();
  171. delay(500);
  172. ProxSetup();
  173. LineSetup();
  174. GyroSetup();
  175. CompassSetup();
  176. //Zumo bereit zu starten
  177. //Serial1.println("Zumo bereit, starte mit A");
  178. ledGreen(1);
  179. buttonA.waitForButton();
  180. randomSeed(millis());
  181. delay(500);
  182. stopUpdate = millis();
  183. //Serial1.println("Start");
  184. }
  185. /*-----------------------------------------------------------------*/
  186. //Update Zeitdifferenz für alle Funktionen
  187. void TimeUpdate()
  188. {
  189. uint16_t m = millis();
  190. eventTime = m - lastUpdate;
  191. }
  192. //Update Zeit für Kontaktvermeiden
  193. void StopUpdate()
  194. {
  195. uint16_t m = millis();
  196. stopTime = m - stopUpdate;
  197. }
  198. void LoopTiming()
  199. {
  200. const int AL = 100; // Arraylänge, NUR GERADE Zahlen verwenden!
  201. static unsigned long LoopTime[AL];
  202. static unsigned int Index=0, Messung=0, Min=0xFFFF, Max, Avg;
  203. if (Messung % 2 == 0) // wenn Messung X gerade (0,2,4,6 usw.), entspricht immer Anfang der Loop
  204. {
  205. LoopTime[Index] = millis();
  206. Messung++;
  207. Index++;
  208. return; // Funktion sofort beenden, spart etwas Zeit
  209. }
  210. if (Messung % 2 == 1) // wenn Messung X ungerade (1,3,5,7 usw.), entspricht immer Ende der Loop
  211. {
  212. LoopTime[Index] = millis();
  213. LoopTime[Index-1] = LoopTime[Index] - LoopTime[Index-1]; // Loopdauer einen Index niedriger einspeichern wie aktuell
  214. Messung++;
  215. }
  216. if (Index >= AL) // Array voll, Daten auswerten
  217. {
  218. for (int i = 0; i<AL; i++)
  219. {
  220. Min = min(Min, LoopTime[i]);
  221. Max = max(Max, LoopTime[i]);
  222. Avg += LoopTime[i];
  223. }
  224. Avg = Avg / AL;
  225. Serial1.print(F("Minimal "));Serial1.print(Min);Serial1.println(" ms ");
  226. Serial1.print(F("Durchschnitt "));Serial1.print(Avg);Serial1.println(" ms ");
  227. Serial1.print(F("Maximal "));Serial1.print(Max);Serial1.println(" ms ");
  228. SerielleAusgabe();
  229. Min = 0xFFFF;
  230. Max = 0;
  231. Avg = 0;
  232. Messung = 0;
  233. Index = 0;
  234. }
  235. }
  236. //Funktion Serielle Ausgabe
  237. void SerielleAusgabe()
  238. {
  239. char report[200];
  240. snprintf_P(report, sizeof(report),
  241. PSTR("Abstand: %d %d %d %d Linie: %d %d %d"),
  242. proxValue[0], proxValue[1], proxValue[2], proxValue[3],
  243. lineValue[0], lineValue[1], lineValue[2]);
  244. Serial1.println(report);
  245. snprintf_P(report, sizeof(report),
  246. PSTR("Weg: %d %d Winkel: %d Beschleunigung: %d"),
  247. driveRotation[0], driveRotation[1], rotationAngle, compassRate);
  248. Serial1.println(report);
  249. }
  250. //Update Abstandssensoren
  251. void ProxUpdate()
  252. {
  253. bool done = false;
  254. int state = LOW;
  255. while(done == false)
  256. {
  257. //wiederholt abfragen, ob bereits gesendet wird (Dauer je 1000 us bzw. 1 ms)
  258. if(pulseIn(20, state, 1000) == 0 && pulseIn(22, state, 1000) == 0 && pulseIn(4, state, 1000) == 0)
  259. //if(pulseIn(22, state, 1000) > 0)
  260. {
  261. //wenn nichts gesendet wird, selbst Messung durchführen
  262. proxSensors.read();
  263. proxValue[0] = ProxFilter0.in(proxSensors.countsLeftWithLeftLeds());
  264. proxValue[1] = ProxFilter1.in(proxSensors.countsFrontWithLeftLeds());
  265. proxValue[2] = ProxFilter2.in(proxSensors.countsFrontWithRightLeds());
  266. proxValue[3] = ProxFilter3.in(proxSensors.countsRightWithRightLeds());
  267. done = true;
  268. }
  269. else
  270. {
  271. //solange fremde Signale empfangen werden, Fehler ausgeben
  272. Serial.println("Fremdmessung erkannt");
  273. }
  274. }
  275. }
  276. //Update Liniensensoren
  277. void LineUpdate()
  278. {
  279. uint16_t lineRaw[3];
  280. lineSensors.read(lineRaw); //lese Messwerte der Liniensensoren aus
  281. lineValue[0] = LineFilter0.in(lineRaw[0] - lineOffset[0]); //ziehe Offsetwerte von Messwerten ab und gib diese in Filter ein
  282. lineValue[1] = LineFilter1.in(lineRaw[1] - lineOffset[1]); //erhält neue mittlere Werte der Filter
  283. lineValue[2] = LineFilter2.in(lineRaw[2] - lineOffset[2]); //"LineFilter.out" um gefilterte Werte auszugeben ohne neue Werte einzugeben
  284. }
  285. //Update Drehbewegungssensor
  286. void GyroUpdate()
  287. {
  288. gyro.read(); //Rohwert 10285 entspricht 90° bzw.
  289. turnRate = gyro.g.z - gyroOffset; //8,75mdps/LSB
  290. uint16_t m = micros();
  291. uint16_t dt = m - gyroLastUpdate;
  292. gyroLastUpdate = m;
  293. int32_t d = (int32_t)turnRate * dt;
  294. turnAngle += (int64_t)d * 14680064 / 17578125;
  295. rotationAngle = (((int32_t)turnAngle >> 16) * 360) >> 16;
  296. }
  297. //Update Beschleunigungssensor
  298. void CompassUpdate()
  299. {
  300. compass.read(); //Rohwert 16384 entspricht 1g (9,81m/s²) bzw. bei +/-2g Messbereich 0,61mg/LSB
  301. int16_t x = compass.a.x - compassOffset;
  302. compassRate = x - compassLastUpdate;
  303. compassLastUpdate = x;
  304. }
  305. //Update Encoder
  306. void EncoderUpdate()
  307. {
  308. encoderCounts[0] += encoders.getCountsAndResetLeft();
  309. driveRotation[0] = encoderCounts[0] / 910; //12cpr (Motorwelle) * 75,81:1 (Getriebe) = 909,7cpr (Antriebszahnrad)
  310. encoderCounts[1] += encoders.getCountsAndResetRight();
  311. driveRotation[1] = encoderCounts[1] / 910;
  312. }
  313. /*-----------------------------------------------------------------*/
  314. //Funktion Kontaktvermeiden
  315. void Kontaktvermeiden()
  316. {
  317. //Serial1.println("Kontaktvermeiden");
  318. Serial1.print(1);
  319. ledRed(1);
  320. motors.setSpeeds(0, 0);
  321. delay(1000);
  322. while(proxValue[1] == 0 || proxValue[2] == 0)
  323. {
  324. ProxUpdate();
  325. LineUpdate();
  326. motors.setSpeeds(-HALFSPEEDLEFT, -HALFSPEEDRIGHT);
  327. if(lineValue[0] > MARKLINE0 || lineValue[1] > MARKLINE1 || lineValue[2] > MARKLINE2) break;
  328. }
  329. lastUpdate = millis();
  330. TimeUpdate();
  331. while(eventTime < 1000)
  332. {
  333. TimeUpdate();
  334. LineUpdate();
  335. motors.setSpeeds(-HALFSPEEDLEFT, -HALFSPEEDRIGHT);
  336. if(lineValue[0] > MARKLINE0 || lineValue[1] > MARKLINE1 || lineValue[2] > MARKLINE2) break;
  337. }
  338. motors.setSpeeds(0, 0);
  339. compassLastUpdate = 0;
  340. compassRate = 0;
  341. CompassUpdate();
  342. stop = false;
  343. stopUpdate = millis();
  344. //Serial1.println("Vermeiden beendet");
  345. Serial1.print(0);
  346. }
  347. //Funktion Hindernisumfahrung
  348. void Hindernisumfahren()
  349. {
  350. //Serial1.println("Hindernisumfahren");
  351. Serial1.print(1);
  352. ledYellow(1);
  353. //Schritt 1: Spurwechsel links
  354. //links drehen
  355. turnAngle = 0;
  356. rotationAngle = 0;
  357. GyroUpdate();
  358. while(rotationAngle < 20)
  359. {
  360. GyroUpdate();
  361. LineUpdate();
  362. motors.setSpeeds(SLOWSPEEDLEFT, FULLSPEEDRIGHT);
  363. }
  364. GyroUpdate();
  365. while(rotationAngle < 45)
  366. {
  367. GyroUpdate();
  368. LineUpdate();
  369. motors.setSpeeds(SLOWSPEEDLEFT, FULLSPEEDRIGHT);
  370. if(lineValue[2] > MARKLINE2 && lineValue[2] < SIGN2) break;
  371. }
  372. //geradeaus über Mittellinie fahren
  373. LineUpdate();
  374. while(lineValue[2] < MARKLINE2)
  375. {
  376. LineUpdate();
  377. motors.setSpeeds(FULLSPEEDLEFT, FULLSPEEDRIGHT);
  378. }
  379. //rechts drehen
  380. GyroUpdate();
  381. while(rotationAngle > 10)
  382. {
  383. GyroUpdate();
  384. LineUpdate();
  385. if(lineValue[0] > MARKLINE0 && lineValue[0] < SIGN0) motors.setSpeeds(FULLSPEEDLEFT, 0);
  386. else if(lineValue[2] > MARKLINE2 && lineValue[2] < SIGN2) motors.setSpeeds(FULLSPEEDLEFT, FULLSPEEDRIGHT);
  387. else motors.setSpeeds(FULLSPEEDLEFT, SLOWSPEEDRIGHT);
  388. }
  389. //geradeaus fahren
  390. motors.setSpeeds(FULLSPEEDLEFT, FULLSPEEDRIGHT);
  391. //Gegenverkehr beachten
  392. ProxUpdate();
  393. //if(proxValue[1] == 6 && proxValue[2] == 6)
  394. //{
  395. //Schritt 2: Hindernis passieren
  396. //Serial1.println("Aufholen");
  397. lastUpdate = millis();
  398. while(proxValue[3] < 6)
  399. {
  400. ProxUpdate();
  401. LineUpdate();
  402. Spurhalten();
  403. TimeUpdate();
  404. //Serial1.println(eventTime);
  405. if(eventTime > 3000) break;
  406. }
  407. //Serial1.println("Vorbeifahren");
  408. ProxUpdate();
  409. while(proxValue[3] == 6)
  410. {
  411. ProxUpdate();
  412. LineUpdate();
  413. Spurhalten();
  414. }
  415. //Serial1.println("Abstand gewinnen");
  416. lastUpdate = millis();
  417. TimeUpdate();
  418. while(eventTime < 3000)
  419. {
  420. LineUpdate();
  421. Spurhalten();
  422. TimeUpdate();
  423. //Serial1.println(eventTime);
  424. }
  425. //}
  426. //Schritt 3: Spurwechsel rechts
  427. //rechts drehen
  428. turnAngle = 0;
  429. rotationAngle = 0;
  430. GyroUpdate();
  431. while(rotationAngle > -20)
  432. {
  433. GyroUpdate();
  434. LineUpdate();
  435. motors.setSpeeds(FULLSPEEDLEFT, SLOWSPEEDRIGHT);
  436. }
  437. GyroUpdate();
  438. while(rotationAngle > -45)
  439. {
  440. GyroUpdate();
  441. LineUpdate();
  442. motors.setSpeeds(FULLSPEEDLEFT, SLOWSPEEDRIGHT);
  443. if(lineValue[0] > MARKLINE0 && lineValue[0] < SIGN0) break;
  444. }
  445. //geradeaus über Mittellinie fahren
  446. LineUpdate();
  447. while(lineValue[0] < MARKLINE0)
  448. {
  449. LineUpdate();
  450. motors.setSpeeds(FULLSPEEDLEFT, FULLSPEEDRIGHT);
  451. }
  452. //links drehen
  453. GyroUpdate();
  454. while(rotationAngle < -10)
  455. {
  456. GyroUpdate();
  457. LineUpdate();
  458. if(lineValue[2] > MARKLINE2 && lineValue[2] < SIGN2) motors.setSpeeds(0, FULLSPEEDRIGHT);
  459. else if(lineValue[0] > MARKLINE0 && lineValue[0] < SIGN0) motors.setSpeeds(FULLSPEEDLEFT, FULLSPEEDRIGHT);
  460. else motors.setSpeeds(SLOWSPEEDLEFT, FULLSPEEDRIGHT);
  461. }
  462. //geradeaus fahren
  463. //Serial1.println("Umfahren beendet");
  464. motors.setSpeeds(FULLSPEEDLEFT, FULLSPEEDRIGHT);
  465. stop = false;
  466. stopUpdate = millis();
  467. Serial1.print(0);
  468. }
  469. //Funktion Abbiegen
  470. void Abbiegen()
  471. {
  472. ledYellow(1);
  473. //Serial1.println("Abbiegen");
  474. Serial1.print(1);
  475. //Markierung analysieren
  476. LineUpdate();
  477. bool leftCode; //links => 1
  478. bool rightCode; //rechts => 2
  479. if((lineValue[0] > SIGN0 && lineValue[0] < 1600) && (lineValue[1] > SIGN1 && lineValue[1] < 800)) leftCode = true;
  480. else leftCode = false;
  481. if((lineValue[2] > SIGN2 && lineValue[2] < 1600) && (lineValue[1] > SIGN1 && lineValue[1] < 800)) rightCode = true;
  482. else rightCode = false;
  483. //Zufallszahl erzeugen
  484. uint8_t randy; //geradeaus => 0
  485. if(leftCode == true && rightCode == true) randy = random(1, 3); //1, 2
  486. else if(leftCode == true && rightCode == false) //randy = 1;
  487. {
  488. randy = random(0, 2); //0, 1
  489. //if(randy == 0) randy = random(0, 2); //erhöht Wahrscheinlickeit abzubiegen
  490. }
  491. else if(leftCode == false && rightCode == true) //randy = 2;
  492. {
  493. randy = random(0, 2); //0, 1
  494. //if(randy == 0) randy = random(0, 2); //erhöht Wahrscheinlickeit abzubiegen
  495. if(randy == 1) randy = 2; //!1 => 2
  496. }
  497. //links Abbiegen (von der Verbindungsstrecke)
  498. if(randy == 1 && rightCode == true)
  499. {
  500. //Serial1.println("links Abbiegen von der Verbindungsstrecke");
  501. //geradeaus zur Mittellinie fahren
  502. motors.setSpeeds(FULLSPEEDLEFT, FULLSPEEDRIGHT+10);
  503. lastUpdate = millis();
  504. TimeUpdate();
  505. while(eventTime < 1000)
  506. {
  507. TimeUpdate();
  508. motors.setSpeeds(FULLSPEEDLEFT, FULLSPEEDRIGHT+10);
  509. }
  510. LineUpdate();
  511. while(lineValue[0] < MARKLINE0 && lineValue[2] < MARKLINE2)
  512. {
  513. LineUpdate();
  514. motors.setSpeeds(FULLSPEEDLEFT, FULLSPEEDRIGHT+10);
  515. }
  516. //links drehen
  517. turnAngle = 0;
  518. rotationAngle = 0;
  519. GyroUpdate();
  520. while(rotationAngle < 90)
  521. {
  522. GyroUpdate();
  523. LineUpdate();
  524. if(lineValue[2] > MARKLINE2 && lineValue[2] < SIGN2) motors.setSpeeds(0, FULLSPEEDRIGHT);
  525. else if(lineValue[0] > MARKLINE0 && lineValue[0] < SIGN0) motors.setSpeeds(HALFSPEEDLEFT, FULLSPEEDRIGHT);
  526. else motors.setSpeeds(SLOWSPEEDLEFT, FULLSPEEDRIGHT);
  527. }
  528. //geradeaus fahren
  529. motors.setSpeeds(FULLSPEEDLEFT, FULLSPEEDRIGHT);
  530. }
  531. //links Abbiegen (vom Rundkurs)
  532. else if(randy == 1 && leftCode == true)
  533. {
  534. //Serial1.println("links Abbiegen vom Rundkurs");
  535. //links drehen
  536. motors.setSpeeds(SLOWSPEEDLEFT, FULLSPEEDRIGHT);
  537. turnAngle = 0;
  538. rotationAngle = 0;
  539. GyroUpdate();
  540. while(rotationAngle < 40)
  541. {
  542. GyroUpdate();
  543. motors.setSpeeds(SLOWSPEEDLEFT, FULLSPEEDRIGHT);
  544. }
  545. GyroUpdate();
  546. while(rotationAngle < 85)
  547. {
  548. GyroUpdate();
  549. motors.setSpeeds(SLOWSPEEDLEFT, FULLSPEEDRIGHT);
  550. }
  551. //geradeaus fahren
  552. motors.setSpeeds(FULLSPEEDLEFT, FULLSPEEDRIGHT);
  553. lastUpdate = millis();
  554. TimeUpdate();
  555. while(eventTime < 1000)
  556. {
  557. TimeUpdate();
  558. LineUpdate();
  559. motors.setSpeeds(FULLSPEEDLEFT, FULLSPEEDRIGHT);
  560. if(lineValue[2] > MARKLINE2 && lineValue[2] < SIGN2) break;
  561. }
  562. lastUpdate = millis();
  563. TimeUpdate();
  564. while(eventTime < 1000)
  565. {
  566. TimeUpdate();
  567. LineUpdate();
  568. Spurhalten();
  569. }
  570. }
  571. //rechts Abbiegen
  572. else if(randy == 2 && rightCode == true)
  573. {
  574. //Serial1.println("rechts Abbiegen");
  575. //rechts drehen
  576. motors.setSpeeds(FULLSPEEDLEFT, SLOWSPEEDRIGHT);
  577. turnAngle = 0;
  578. rotationAngle = 0;
  579. GyroUpdate();
  580. while(rotationAngle > -40)
  581. {
  582. GyroUpdate();
  583. LineUpdate();
  584. motors.setSpeeds(FULLSPEEDLEFT, SLOWSPEEDRIGHT);
  585. if(lineValue[0] > MARKLINE0 && lineValue[0] < SIGN0) break;
  586. }
  587. GyroUpdate();
  588. lastUpdate = millis();
  589. while(rotationAngle > -85)
  590. {
  591. TimeUpdate();
  592. GyroUpdate();
  593. LineUpdate();
  594. if(eventTime > 3000) break;
  595. if(lineValue[0] > MARKLINE0 && lineValue[0] < SIGN0) motors.setSpeeds(FULLSPEEDLEFT, 0);
  596. //else if(lineValue[1] > MARKLINE1 && lineValue[1] < SIGN1) motors.setSpeeds(-SLOWSPEEDLEFT, -SLOWSPEEDRIGHT);
  597. else if(lineValue[2] > MARKLINE2 && lineValue[2] < SIGN2) motors.setSpeeds(FULLSPEEDLEFT, HALFSPEEDRIGHT);
  598. else motors.setSpeeds(FULLSPEEDLEFT, SLOWSPEEDRIGHT);
  599. }
  600. }
  601. //nicht Abbiegen, geradeaus fahren
  602. else
  603. {
  604. //Serial1.println("nicht Abbiegen");
  605. motors.setSpeeds(FULLSPEEDLEFT, FULLSPEEDRIGHT);
  606. lastUpdate = millis();
  607. TimeUpdate();
  608. while(eventTime < 1000)
  609. {
  610. TimeUpdate();
  611. LineUpdate();
  612. Spurhalten();
  613. }
  614. }
  615. stop = false;
  616. stopUpdate = millis();
  617. //Serial1.println("Abbiegen beendet");
  618. Serial1.print(0);
  619. }
  620. //Funktion Spurhalten
  621. void Spurhalten()
  622. {
  623. uint16_t StartTime = millis();
  624. uint16_t Update = millis();
  625. uint16_t Time = Update - StartTime;
  626. //linke Linie erreicht, nach rechts fahren
  627. if(lineValue[0] > MARKLINE0 && lineValue[0] < SIGN0)
  628. {
  629. ledYellow(1);
  630. //Serial1.println("Spur nach rechts korrigieren");
  631. motors.setSpeeds((int)FULLSPEEDLEFT/eventSpeed, (int)SLOWSPEEDRIGHT/eventSpeed);
  632. while(Time < 100)
  633. {
  634. Update = millis();
  635. Time = Update - StartTime;
  636. LineUpdate();
  637. if(lineValue[2] > MARKLINE2) break;
  638. }
  639. stop = false;
  640. stopUpdate = millis();
  641. }
  642. //rechte Linie erreicht, nach links fahren
  643. else if(lineValue[2] > MARKLINE2 && lineValue[2] < SIGN2)
  644. {
  645. ledYellow(1);
  646. //Serial1.println("Spur nach links korrigieren");
  647. motors.setSpeeds((int)SLOWSPEEDLEFT/eventSpeed, (int)FULLSPEEDRIGHT/eventSpeed);
  648. while(Time < 100)
  649. {
  650. Update = millis();
  651. Time = Update - StartTime;
  652. LineUpdate();
  653. if(lineValue[0] > MARKLINE0) break;
  654. }
  655. stop = false;
  656. stopUpdate = millis();
  657. }
  658. //normale Fahrt
  659. else
  660. {
  661. ledGreen(1);
  662. motors.setSpeeds((int)FULLSPEEDLEFT/eventSpeed, (int)FULLSPEEDRIGHT/eventSpeed);
  663. stop = true;
  664. }
  665. }
  666. //Funktion Spurfinden
  667. void Spurfinden()
  668. {
  669. ledRed(1);
  670. //Serial1.println("Spurfinden");
  671. Serial1.print(1);
  672. lastUpdate = millis();
  673. while(lineValue[0] < MARKLINE0 && lineValue[2] < MARKLINE2) //Zumo fährt solange rückwärst bis er wieder auf der Spur steht
  674. {
  675. TimeUpdate();
  676. LineUpdate();
  677. motors.setSpeeds(-FULLSPEEDLEFT, -FULLSPEEDRIGHT);
  678. if(eventTime > 3000) break;
  679. }
  680. stop = false;
  681. stopUpdate = millis();
  682. //Serial1.println("Spur gefunden");
  683. Serial1.print(0);
  684. }
  685. /*-----------------------------------------------------------------*/
  686. void loop()
  687. {
  688. //LoopTiming(); //Zykluszeit beträgt max. 20ms im Idle
  689. ledGreen(0);
  690. ledYellow(0);
  691. ledRed(0);
  692. //Abfragen der Sensordaten
  693. ProxUpdate();
  694. EncoderUpdate();
  695. GyroUpdate();
  696. CompassUpdate();
  697. LineUpdate();
  698. TimeUpdate();
  699. StopUpdate();
  700. //Funktionsauswahl
  701. if(Serial1.available() > 0) btData = Serial1.read();
  702. if(btData == '1') btBuffer = true;
  703. else if(btData == '0') btBuffer = false;
  704. //verfügbare Funktionen bei laufenden Manövern
  705. if(btBuffer == true)
  706. {
  707. //Serial1.println("Verstanden");
  708. eventSpeed = 1.4;
  709. if(proxValue[0] == 6 || (proxValue[1] == 6 && proxValue[2] == 6)) motors.setSpeeds(0, 0);
  710. else if(stop == true && stopTime > 2000 && abs(compassRate) > 3500) motors.setSpeeds(0, 0);
  711. else if(lineValue[0] > SIGN0 || lineValue[2] > SIGN2 || lineValue[1] > MARKLINE1) motors.setSpeeds(0, 0);
  712. else Spurhalten();
  713. }
  714. //verfügbare Funktionen im Normalfall
  715. else
  716. {
  717. eventSpeed = 1.0;
  718. if(stop == true && stopTime > 2000 && abs(compassRate) > 3500) Kontaktvermeiden();
  719. else if(proxValue[1] == 6 && proxValue[2] == 6) Hindernisumfahren();
  720. else if(lineValue[0] > 1600 && lineValue[2] > 1600) motors.setSpeeds(0, 0);
  721. else if((lineValue[0] > SIGN0 && lineValue[0] < 1600) && (lineValue[1] > SIGN1 && lineValue[1] < 800)) Abbiegen();
  722. else if((lineValue[2] > SIGN2 && lineValue[2] < 1600) && (lineValue[1] > SIGN1 && lineValue[1] < 800)) Abbiegen();
  723. else if(lineValue[1] > MARKLINE1 && lineValue[1] < SIGN1) Spurfinden();
  724. else Spurhalten();
  725. }
  726. //LoopTiming();
  727. }