Hauptprojekt.ino.cpp 25 KB

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