Roboshark / Mbed 2 deprecated Roboshark_V10

Dependencies:   mbed

Fork of Roboshark_V9 by Roboshark

Revision:
14:feafcee53fed
Parent:
10:fb2195d0de0f
Child:
15:8e8b23d4abb4
diff -r 1687f97d4d82 -r feafcee53fed main.cpp
--- a/main.cpp	Wed May 09 17:08:24 2018 +0000
+++ b/main.cpp	Mon May 14 22:11:47 2018 +0000
@@ -1,9 +1,9 @@
-/*Roboshark V7
+/*Roboshark V10
 main.cpp
 Erstellt: J. Blunschi
 geändert: V.Ahlers
 V.5.18
-main zu Robishark V4
+main zu Robishark
 */
 
 
@@ -16,22 +16,24 @@
 
 DigitalOut myled(LED1);
 
-DigitalOut led0(PC_8);
-DigitalOut led1(PC_6);
-DigitalOut led2(PB_12);
+DigitalOut led0(PC_8);              //Ready
+DigitalOut ledLinksAktiv(PC_6);     // Links Aktiv
+DigitalOut ledRechtsAktiv(PB_12);   // Rechts Aktiv
 DigitalOut led3(PA_7);
 DigitalOut led4(PC_0);
 DigitalOut led5(PC_9);
 
-AnalogIn LineSensor(PB_1); // Line Sensor
 DigitalOut enable(PC_1);
 DigitalOut bit0(PH_1);
 DigitalOut bit1(PC_2);
 DigitalOut bit2(PC_3);
 
-AnalogIn IrRight(PC_3);                                                         //von main Vincent kopiert
+AnalogIn IrRight(PC_3);         // IR Sensoren
 AnalogIn IrLeft (PC_5);
 AnalogIn IrFront(PC_2);
+AnalogIn LineSensor(PB_1);     // Line Sensor
+DigitalIn button (USER_BUTTON); //Auswählen ob Rechts oder Links methode
+
 float disR = 0;
 float disL = 0;
 float disF = 0;
@@ -50,7 +52,9 @@
 int temp = 0;   
 float SpeedR = 0;
 float SpeedL = 0;
-int reglerEin = 0;
+int links = 0;
+int linksLast = 0;
+int skip = 0;
                                                      //von main Vincent kopiert
 
 DigitalOut enableMotorDriver(PB_2);
@@ -69,15 +73,38 @@
 
 Fahren fahren(controller, counterLeft, counterRight, iRSensor);                           //Reihenfolge!!!!!!!!!!!!!!!!!!! Ultra wichtig
 
-int main()
-{
+int main(){
+    led0 = 1;
 
-    //controller.setDesiredSpeedLeft(150.0f); // Drehzahl in [rpm]              //DEFAULT VON TOBI
-    //controller.setDesiredSpeedRight(-150.0f);                                 //DEFAULT VON TOBI
     enable = 1;
-    enableMotorDriver = 1;                                                      // Schaltet den Leistungstreiber ein
+    enableMotorDriver = 1;                                               // Schaltet den Leistungstreiber ein
+    
     while(1) {
-
+         
+         if (button == 1){
+            temp = 0;
+            ende = 0;
+            skip = 0;
+            }
+        
+        if(button != linksLast){                                       // Zustand button speichern
+             links = 1;
+             } else { links = 0;
+             }
+        linksLast = button;
+        
+        if ((links == 0) && (skip == 0)){
+            ledRechtsAktiv = 1;
+            ledLinksAktiv = 0;
+            wait (2);
+            skip = 1;
+            } else { if ((links == 1) && ( skip == 0)){
+                ledLinksAktiv = 1;
+                ledRechtsAktiv = 0;
+                wait (2);
+                skip = 1;
+                }
+            }
                                                                          // IR Sensoren einlesen
         float disR = iRSensor.readR(); // Distanz in mm
         float disL = iRSensor.readL();
@@ -101,25 +128,51 @@
         printf("IR Left = %d\n",IrL);
         printf("IR Front = %d\n",IrF);*/
         
+    while ((links == 0) && (skip == 1)){                                                          // State machine für methode Rechts
          if((IrR==0) && (IrL==0) && (IrF==1) && (ende == 0)){
-        caseDrive = 2;                                                          // Folge: 90 Grad nach rechts drehen
+        caseDrive = 2;                                                          
         }   else  if ((IrR==0) && (IrL==1) && (IrF==0) && (ende == 0)){
-        caseDrive = 2;                                                          // Folge: 90 Grad nach rechts drehen
+        caseDrive = 2;                                                          
         }   else  if ((IrR==0) && (IrL==1) && (IrF==1) && (ende == 0)){
-        caseDrive = 2;                                                          // Folge: 90 Grad nach rechts drehen                 
+        caseDrive = 2;                                                                        
         }   else  if ((IrR==1) && (IrL==0) && (IrF==0) && (ende == 0)){
-        caseDrive = 1;                                                          // Folge: geradeaus fahren
+        caseDrive = 1;                                                          
         }   else  if ((IrR==1) && (IrL==0) && (IrF==1) && (ende == 0)){
-        caseDrive = 3;                                                          // Folge: 90 Grad nach Links drehen
+        caseDrive = 3;                                                          
         }   else  if ((IrR==1) && (IrL==1) && (IrF==0) && (ende == 0)){
-        caseDrive = 1;                                                          // Folge: geradeaus fahren
+        caseDrive = 1;                                                       
         }   else  if ((IrR==1) && (IrL==1) && (IrF==1) && (ende == 0)){
-        caseDrive = 4;                                                           // Folge: 180 Grad nach rechts drehen
+        caseDrive = 4;                                                           
         } else if ((ende == 1) && (temp == 0)){
-        caseDrive = 5;                                                          // Folge: Ziel erreicht
+        caseDrive = 5;                                                          
         temp = 1;
-        } else {caseDrive = 0;                                                  // Folge; Stop
+        } else {caseDrive = 0;                                                  
         }
+    }
+    while ((links == 1) && (skip == 1)){                                                        //State Machine für Methode Links
+        if((IrR==0) && (IrL==0) && (IrF==0) && (ende == 0)){
+        caseDrive = 3;                                                          
+        }   else  if ((IrR==1) && (IrL==0) && (IrF==0) && (ende == 0)){
+        caseDrive = 3;                                                       
+        }   else  if ((IrR==0) && (IrL==1) && (IrF==0) && (ende == 0)){
+        caseDrive = 1;                                                                          
+        }   else  if ((IrR==1) && (IrL==1) && (IrF==0) && (ende == 0)){
+        caseDrive = 1;                                                          
+        }   else  if ((IrR==0) && (IrL==0) && (IrF==1) && (ende == 0)){
+        caseDrive = 3;                                                          
+        }   else  if ((IrR==1) && (IrL==0)&& (IrF==1)&& (ende == 0)){
+        caseDrive = 3;                                                         
+        }   else  if ((IrR==0)&& (IrL==1) && (IrF==1) && (ende == 0)){
+        caseDrive = 2;
+        }   else  if ((IrR==1)&& (IrL==1) && (IrF==1) && (ende == 0)){
+        caseDrive = 4;                                                                 
+        } else if ((ende == 1) && (temp == 0)){
+        caseDrive = 5;                                                          
+        temp = 1;
+        } else {caseDrive = 0;                                                  
+        }
+    }
+
 
       //  printf("caseDrive = %d\n",caseDrive);
         //printf("ende = %d\n",ende);