Roboshark / Mbed 2 deprecated IrSensorDistanceMessureFornt

Dependencies:   mbed

Fork of IrSensorDistanceMessure by Roboshark

Revision:
1:8184ab7e4395
Parent:
0:a49ea5211c34
diff -r a49ea5211c34 -r 8184ab7e4395 main.cpp
--- a/main.cpp	Sun May 06 10:31:08 2018 +0000
+++ b/main.cpp	Sun May 06 12:50:45 2018 +0000
@@ -3,48 +3,33 @@
  //Distandce Messure IR Sensor
  //Meas = f(s)
  
-AnalogIn analog_value(PC_3);
-AnalogIn analog_value2(PC_5);
+AnalogIn analog_value(PC_2);
 
-    const float PR1 = 3.4734*0.000000001;    //Koeffizienten
-    const float PR2 = -7.1846*0.000001;
-    const float  PR3 = 0.0055;
-    const float PR4 = -1.9304;
-    const float PR5 = 301.2428;
-    const float PL1 = 3.4734*0.000000001;
-    const float PL2 = -7.1846*0.000001;
-    const float PL3 = 0.0055;
-    const float  PL4 = -1.9304;
-    const float  PL5 = 301.2428;
-    float disL;
-    float disR;
-    int roundL;
-    int roundR;
+    const float PF1 = 6.1767f*pow(10.0f,-10);
+    const float PF2 = -1.9975f*pow(10.0f,-6);
+    const float PF3 = 0.0024f;
+    const float PF4 = -1.3299f;
+    const float PF5 = 351.1557f;
+    float disF;
+    int roundF;
     
 int main() {
-    float measL;
-    float measR;
-    printf("\nDistance Test Sensoren Rechts und Links\n");
+    
+    float measF;
+    printf("\nDistance Test Sensoren Front\n");
     printf("misst die Distanz vom Wagenrad bis Objekt\n");
     wait(1.5);
     
     while(1) {
-        measR = analog_value.read(); // Converts and read the analog input value (value from 0.0 to 1.0)
-        measR = measR * 1000; // Change the value to be in the 0 to 1000 range
-        disR = PR1*pow(measR,4)+PR2*pow(measR,3)+PR3*pow(measR,2)+PR4*measR+PR5; //disR = f(measR)
-        roundR = disR*100;
-        disR = roundR/100.0-10.0;
+
         
-        printf("Distanz R = %f\n", disR);
-      
+        measF = analog_value.read(); // Converts and read the analog input value (value from 0.0 to 1.0)
+        measF = measF * 1000; // Change the value to be in the 0 to 1000 range
+        disF = PF1*pow(measF,4)+PF2*pow(measF,3)+PF3*pow(measF,2)+PF4*measF+PF5; //disF = f(measF)
+        roundF = disF*100;
+        disF = roundF/100.0-20.0;
         
-        measL = analog_value2.read(); // Converts and read the analog input value (value from 0.0 to 1.0)
-        measL = measL * 1000; // Change the value to be in the 0 to 1000 range
-        disL = PL1*pow(measL,4)+PL2*pow(measL,3)+PL3*pow(measL,2)+PL4*measL+PL5; //disL = f(measL)
-        roundL = disL*100;
-        disL = roundL/100.0-10.0;
-        
-        printf("Distanz L = %f\n", disL);
+        printf("Distanz Front = %f\n", disF);
         
         wait(0.7); // 1 s
     }