Roboshark / Mbed 2 deprecated Roboshark_V10

Dependencies:   mbed

Fork of Roboshark_V9 by Roboshark

Files at this revision

API Documentation at this revision

Comitter:
ahlervin
Date:
Tue May 15 21:50:26 2018 +0000
Parent:
14:feafcee53fed
Commit message:
mit Links Hand Methode

Changed in this revision

Fahren.cpp Show annotated file Show diff for this revision Revisions of this file
IRSensor.cpp Show annotated file Show diff for this revision Revisions of this file
IRSensor.h Show annotated file Show diff for this revision Revisions of this file
main.cpp Show annotated file Show diff for this revision Revisions of this file
--- a/Fahren.cpp	Mon May 14 22:11:47 2018 +0000
+++ b/Fahren.cpp	Tue May 15 21:50:26 2018 +0000
@@ -17,8 +17,8 @@
 //Konstruktor
 Fahren::Fahren(Controller& controller, EncoderCounter& counterLeft, EncoderCounter& counterRight, IRSensor& iRSensor):
     controller(controller), counterLeft(counterLeft), counterRight(counterRight), iRSensor (iRSensor){
-SpeedR = 120.0f; //120
-SpeedL = 120.0f; //120
+SpeedR = 90.0f; //120
+SpeedL = 90.0f; //120
 disF = 0.0f;
 //ticker.attach(callback(this, &Fahren::reset), PERIOD);
 }
@@ -50,13 +50,13 @@
     reglerEinL = 1;
     
     while(1){
-    float diff = (iRSensor.readR() - iRSensor.readL())*0.81f;            //Regler 0.81
-    if(iRSensor.readR()>80.0f) diff=0;
-    if(iRSensor.readL()>80.0f) diff=0;
+    float diff = (iRSensor.readR() - iRSensor.readL())*0.95f;            //Regler 0.81
+    if(iRSensor.readR()>80.0f) diff= 0;
+    if(iRSensor.readL()>80.0f) diff= 0;
     //printf("diff =%f \n",diff);
     controller.setDesiredSpeedRight(SpeedR+diff);
     controller.setDesiredSpeedLeft(-(SpeedL-diff));
-    
+    printf("diff = %f\n",diff);
     wait(0.02); //0.02
        
        // printf("Encoderrechts %d \n\r", counterRight.read());                   //Debugging Zweck (Putty benutzen!)
--- a/IRSensor.cpp	Mon May 14 22:11:47 2018 +0000
+++ b/IRSensor.cpp	Tue May 15 21:50:26 2018 +0000
@@ -37,8 +37,8 @@
 
 
 
-IRSensor::IRSensor(AnalogIn& IrRight, AnalogIn& IrLeft, AnalogIn& IrFront, float dis2R, float dis2L, float dis2F, AnalogIn& LineSensor) : 
-IrRight(IrRight), IrLeft(IrLeft), IrFront(IrFront), dis2R(dis2R), dis2L(dis2L), dis2F(dis2F), LineSensor(LineSensor){
+IRSensor::IRSensor(AnalogIn& IrRight, AnalogIn& IrLeft, AnalogIn& IrFront, float dis2R, float dis2L, float dis2F, AnalogIn& LineSensor, DigitalIn& button) : 
+IrRight(IrRight), IrLeft(IrLeft), IrFront(IrFront), dis2R(dis2R), dis2L(dis2L), dis2F(dis2F), LineSensor(LineSensor), button(button){
     ticker.attach(callback(this, &IRSensor::codeB), Period);
       this-> ende = ende;
       ende = 0;
@@ -124,7 +124,15 @@
         if (line == 1) {
         ende = 1;
 }
+        if (button == 0){
+        ende = 0;
+        finish = 0;
+        finishLast = 0;
+}
         finishLast = finish;    
+        
+       /// printf("Ende = %d\n",ende);
+       // printf("BL = %d\n",button);
     return;
 }
 
--- a/IRSensor.h	Mon May 14 22:11:47 2018 +0000
+++ b/IRSensor.h	Tue May 15 21:50:26 2018 +0000
@@ -15,7 +15,7 @@
  class IRSensor {
     
     public:
-        IRSensor(AnalogIn& IrRight, AnalogIn& IrLeft, AnalogIn& IrFront, float dis2R, float dis2L, float dis2F, AnalogIn& LineSensor); 
+        IRSensor(AnalogIn& IrRight, AnalogIn& IrLeft, AnalogIn& IrFront, float dis2R, float dis2L, float dis2F, AnalogIn& LineSensor, DigitalIn& button); 
         
         float disR;
         float disL;
@@ -45,9 +45,11 @@
         AnalogIn& IrLeft;
         AnalogIn& IrFront;
         AnalogIn& LineSensor;
+        DigitalIn button;
         float dis2R;
         float dis2L;
         float dis2F;
+        int BL;
         int roundL;
         int roundR;
         int roundF;
--- a/main.cpp	Mon May 14 22:11:47 2018 +0000
+++ b/main.cpp	Tue May 15 21:50:26 2018 +0000
@@ -55,6 +55,7 @@
 int links = 0;
 int linksLast = 0;
 int skip = 0;
+int BL = 1;
                                                      //von main Vincent kopiert
 
 DigitalOut enableMotorDriver(PB_2);
@@ -67,44 +68,26 @@
 EncoderCounter counterLeft(PB_6, PB_7);
 EncoderCounter counterRight(PA_6, PC_7);
 
-IRSensor iRSensor(IrRight, IrLeft, IrFront, dis2R, dis2L, dis2F, LineSensor);          //von main Vincent kopiert
+IRSensor iRSensor(IrRight, IrLeft, IrFront, dis2R, dis2L, dis2F, LineSensor, button);          //von main Vincent kopiert
 
 Controller controller(pwmLeft, pwmRight, counterLeft, counterRight);
 
 Fahren fahren(controller, counterLeft, counterRight, iRSensor);                           //Reihenfolge!!!!!!!!!!!!!!!!!!! Ultra wichtig
 
 int main(){
-    led0 = 1;
 
     enable = 1;
     enableMotorDriver = 1;                                               // Schaltet den Leistungstreiber ein
     
     while(1) {
-         
-         if (button == 1){
-            temp = 0;
-            ende = 0;
-            skip = 0;
-            }
+
         
-        if(button != linksLast){                                       // Zustand button speichern
+        if(button == linksLast){
              links = 1;
+             linksLast = links;
              } 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();
@@ -117,6 +100,21 @@
         int IrF = iRSensor.codeF();
         ende = iRSensor.get_ende();     // Line erkennt = 1
 
+         BL = button;
+         if (button == 0){
+            temp = 0;
+            ende = 0;
+            skip = 0;
+            }
+            
+            if ((links == 0) && (skip == 0)){
+            wait (1);
+            skip = 1;
+            } else { if ((links == 1) && ( skip == 0)){
+                wait (1);
+                skip = 1;
+                }
+            }
 
    
    /* printf (" ende = %d\n",ende); 
@@ -128,7 +126,8 @@
         printf("IR Left = %d\n",IrL);
         printf("IR Front = %d\n",IrF);*/
         
-    while ((links == 0) && (skip == 1)){                                                          // State machine für methode Rechts
+    switch(links) {
+         case 0:                                                           // State machine für methode Rechts
          if((IrR==0) && (IrL==0) && (IrF==1) && (ende == 0)){
         caseDrive = 2;                                                          
         }   else  if ((IrR==0) && (IrL==1) && (IrF==0) && (ende == 0)){
@@ -148,8 +147,9 @@
         temp = 1;
         } else {caseDrive = 0;                                                  
         }
-    }
-    while ((links == 1) && (skip == 1)){                                                        //State Machine für Methode Links
+        break;
+        
+        case 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)){
@@ -160,7 +160,7 @@
         caseDrive = 1;                                                          
         }   else  if ((IrR==0) && (IrL==0) && (IrF==1) && (ende == 0)){
         caseDrive = 3;                                                          
-        }   else  if ((IrR==1) && (IrL==0)&& (IrF==1)&& (ende == 0)){
+        }   else  if ((IrR==1) && (IrL==0)&& (IrF==1) && (ende == 0)){
         caseDrive = 3;                                                         
         }   else  if ((IrR==0)&& (IrL==1) && (IrF==1) && (ende == 0)){
         caseDrive = 2;
@@ -174,8 +174,7 @@
     }
 
 
-      //  printf("caseDrive = %d\n",caseDrive);
-        //printf("ende = %d\n",ende);
+        printf("ende = %d\n",ende);
 
         wait (0.01);