Josimar Hernandez / Mbed 2 deprecated CUADRUPEDO

Dependencies:   mbed

Revision:
2:ee9eb5f76979
Parent:
1:7d7dabfcd7ae
Child:
3:8bc95fb7c59c
--- a/main.cpp	Mon Oct 08 23:25:59 2018 +0000
+++ b/main.cpp	Tue Nov 20 01:56:56 2018 +0000
@@ -1,15 +1,20 @@
 #include "mbed.h"
 #include "main.h"
 
+
 int Conf_Servos();
 int ConfTransmi();
-int RutColor();
+void RutColor();
+void Joy();
 void MoverMotor (uint8_t motor, uint8_t grados);
 void MoverConjunto(uint8_t motores, uint8_t posicion);
 
+
 DigitalIn entrada (PE_15);
 DigitalOut S3 (PB_0);
 DigitalOut S2 (PE_0);
+AnalogIn analog_1(A0);
+DigitalOut led(LED1);
 
 PwmOut Servo1(PB_11);
 PwmOut Servo2(PB_10);
@@ -70,11 +75,17 @@
 break;
 }
 case 0x03:{
-while (funcion==0x03){
+  
     RutColor();
-    }    
+break;
+    } 
+
+case 0x04:{
+    Joy();
     }
-    
+
+        
+
 default:{
 Transmi.printf("Funcion no definida. \n");
         }
@@ -352,7 +363,7 @@
     return(0);
     }
 
-int RutColor(){
+void  RutColor(){
     
                 S2=0;
                 S3=0;
@@ -366,20 +377,102 @@
                 S3=1;
                 verde=Detectar();
                 
-                if (rojo<azul & azul<verde){
-                    color=rojo;
-                    RutRojo();
+                if ((rojo>2)&(rojo<25) & (azul>35)&(azul<54) & (verde>53)&(verde<73)){
+                    Transmi.printf("rojo. \n");
+            Servo1.pulsewidth_us(1025);
+            wait (0.5);
+            Servo2.pulsewidth_us(1319);
+            wait (0.5);     
+            Servo1.pulsewidth_us(1412);
+            wait (0.5);     
+            Servo7.pulsewidth_us(1025);
+            wait (0.5);
+            Servo8.pulsewidth_us(1809);
+            wait (0.5);
+            Servo7.pulsewidth_us(1417);
+            wait (0.5);
+            Servo2.pulsewidth_us(1515);
+            Servo8.pulsewidth_us(1515);
+            wait (0.5);
+            Servo3.pulsewidth_us(1221);
+            wait (0.5);
+            Servo4.pulsewidth_us(1613);
+            wait (0.5);
+            Servo3.pulsewidth_us(1613);
+            wait (0.5);
+            Servo5.pulsewidth_us(731);
+            wait (0.5);
+            Servo6.pulsewidth_us(1025);
+            wait (0.5);
+            Servo5.pulsewidth_us(1025);
+            wait (0.5);
+            Servo4.pulsewidth_us(1417);
+            Servo6.pulsewidth_us(1417);
+            wait (0.5);
                     }
                     
                     else{
-                        if (azul<rojo & rojo<verde){
-                          color=azul;  
-                           RutAzul(); 
-                           }
+                        if ((rojo>130)&(rojo<152) & (azul>35)&(azul<56) & (verde>91)&(verde<114)){
+                                Transmi.printf("azul. \n");
+                                  Servo1.pulsewidth_us(1025);
+            wait (0.5);
+            Servo2.pulsewidth_us(1711);
+            wait (0.5);     
+            Servo1.pulsewidth_us(1412);
+            wait (0.5);     
+            Servo7.pulsewidth_us(1025);
+            wait (0.5);
+            Servo8.pulsewidth_us(1319);
+            wait (0.5);
+            Servo7.pulsewidth_us(1417);
+            wait (0.5);
+            Servo2.pulsewidth_us(1515);
+            Servo8.pulsewidth_us(1515);
+            wait (0.5);
+            Servo3.pulsewidth_us(1221);
+            wait (0.5);
+            Servo4.pulsewidth_us(1025);
+            wait (0.5);
+            Servo3.pulsewidth_us(1613);
+            wait (0.5);
+            Servo5.pulsewidth_us(731);
+            wait (0.5);
+            Servo6.pulsewidth_us(1613);
+            wait (0.5);
+            Servo5.pulsewidth_us(1025);
+            wait (0.5);
+            Servo4.pulsewidth_us(1417);
+            Servo6.pulsewidth_us(1417);
+            wait (0.5); 
+                            }
                            
                             else{
-                                RutVerde();
-                                color=verde;
+                                
+                                if ((rojo>10)&(rojo<24) & (azul>25)&(azul<36) & (verde>23)&(verde<34)){
+                                    Transmi.printf("verde. \n");
+                                Servo1.pulsewidth_us(700);
+                                wait (1);
+                                Servo3.pulsewidth_us(700);
+                                wait (1);
+                                Servo5.pulsewidth_us(700);
+                                wait (1);
+                                Servo7.pulsewidth_us(700);
+                                wait (1);
+                                Servo3.pulsewidth_us(700);
+                                wait (1);
+                                Servo1.pulsewidth_us(1500);
+                                wait (1);
+                                Servo3.pulsewidth_us(1500);
+                                wait (1);
+                                Servo5.pulsewidth_us(1500);
+                                wait (1);
+                                Servo7.pulsewidth_us(1500);
+                                wait (1);
+                                  
+                                
+                            }
+                            else{
+                            Transmi.printf("color no valido. \n");}
                          }
                     }
                 }       
@@ -400,61 +493,105 @@
     tiempo.reset();
     return(tme);
     
+}
+
+void Joy(){
     
-    }
+    
     
     
-int RutRojo(){
-    MoverConjunto(1,0x1A);
-    MoverConjunto(3,0x1A);
-    wait (2);
-    
-    MoverConjunto(2,0xDD);
-    MoverConjunto(4,0xDD);
-    wait (2);
-    
-    MoverConjunto(1,0xDD);
-    MoverConjunto(3,0xDD);
-    wait (2);
-    
-    MoverConjunto(2,0x1A);
-    MoverConjunto(4,0x1A);
-    wait (2);
-    }
-    
-int RutAzul(){
-    
-    MoverConjunto(1,0x1A);
-    MoverConjunto(3,0x1A);
-    wait (2);
+    float medir_r;
+    float medir_v;
+  
     
-    MoverConjunto(2,0x1A);
-    MoverConjunto(4,0x1A);
-    wait (2);
-    
-    MoverConjunto(1,0xDD);
-    MoverConjunto(3,0xDD);
-    wait (2);
-    
-    MoverConjunto(2,0xDD);
-    MoverConjunto(4,0xDD);
-    wait (2);
-    }
+    printf("MANDO\n");
+
+    while(funcion==4) {
+
+        medir_r = analog_1.read(); // Lee el valor de entrada analógica (valor de 0.0 a 1.0 = rango de conversión de ADC completo)
+
+        medir_v = medir_r * 3300; // Convierte valor en el rango 0V-3.3V.
+
+        
+        // Display values
+     //   printf("medida = %f = %.0f mV\n", medir_r, medir_v);
+
+        
+// El LED está encendido si el valor está por debajo de 1 V
+        if (medir_v < 1000) {             
+              
+            Servo1.pulsewidth_us(1025);
+            Servo2.pulsewidth_us(1319);
+            wait (0.5);     
+            Servo1.pulsewidth_us(1412);
+            wait (0.5);
+                 
+            Servo7.pulsewidth_us(1025);
+            Servo8.pulsewidth_us(1809);
+            wait (0.5);
+            Servo7.pulsewidth_us(1417);
+            wait (0.5);
+            
+            Servo2.pulsewidth_us(1515);
+            Servo8.pulsewidth_us(1515);
+            wait (0.5);
+            Servo3.pulsewidth_us(1221);
+            Servo4.pulsewidth_us(1613);
+            wait (0.5);
+            Servo3.pulsewidth_us(1613);
+            wait (0.5);
+            
+            Servo5.pulsewidth_us(731);
+            Servo6.pulsewidth_us(1025);
+            wait (0.5);
+            Servo5.pulsewidth_us(1025);
+            wait (0.5);
+            
+            Servo4.pulsewidth_us(1417);
+            Servo6.pulsewidth_us(1417);
+            wait (0.5);
+             
+             
+             
+             // LED ON
+           
+        } else {
+            if (medir_v > 2000){
+                 wait (0.5);
+            Servo2.pulsewidth_us(1711);
+            wait (0.5);     
+            Servo1.pulsewidth_us(1412);
+            wait (0.5);     
+            Servo7.pulsewidth_us(1025);
+            wait (0.5);
+            Servo8.pulsewidth_us(1319);
+            wait (0.5);
+            Servo7.pulsewidth_us(1417);
+            wait (0.5);
+            Servo2.pulsewidth_us(1515);
+            Servo8.pulsewidth_us(1515);
+            wait (0.5);
+            Servo3.pulsewidth_us(1221);
+            wait (0.5);
+            Servo4.pulsewidth_us(1025);
+            wait (0.5);
+            Servo3.pulsewidth_us(1613);
+            wait (0.5);
+            Servo5.pulsewidth_us(731);
+            wait (0.5);
+            Servo6.pulsewidth_us(1613);
+            wait (0.5);
+            Servo5.pulsewidth_us(1025);
+            wait (0.5);
+            Servo4.pulsewidth_us(1417);
+            Servo6.pulsewidth_us(1417);
+            wait (0.5); 
+                
+        }
     
-int RutVerde(){
-    MoverConjunto(1,0x1A);
-    MoverConjunto(3,0xDD);
-    wait (2);
-    
-    MoverConjunto(2,0xDD);
-    MoverConjunto(4,0x1A);
-    wait (2);
-    
-    MoverConjunto(1,0x1A);
-    MoverConjunto(3,0xDD);
-    wait (2);
-    
-    MoverConjunto(2,0xDD);
-    MoverConjunto(4,0x1A);
-    wait (2);
-    }
\ No newline at end of file
+        wait (1.0);
+        }
+        }
+        }
+
+    
\ No newline at end of file