Se leen comando por el puerto serial realiza las siguientes funciones según el comando: - Genera distintos tonos por un buzzer. - Controla el movimiento de un carro (con 2 motores) con comandos - Controla el movimiento de un carro (con 2 motores) con Joystick. - Lee y envía el color leido por el puerto serial al PC

Dependencies:   mbed

Revision:
0:3a37f6734913
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Motor.cpp	Fri Sep 03 05:22:19 2021 +0000
@@ -0,0 +1,180 @@
+#include "mbed.h"
+#include "Motor.h"
+#include "Ticker.h"
+
+#define Pi 3.14159265
+#define Horario         1
+#define AntiHorario     0
+
+///************  MOTOR CONTINUO ********************************//
+
+/// CONSTRUCTOR
+MotorContinuo::MotorContinuo(PinName _L1, PinName _L2, PinName _speedPin, PinName _encodin, PinName _PosInicial, int _EncodPulses) :
+L1(_L1), L2(_L2), speedPin(_speedPin), encodin(_encodin), PosInicial(_PosInicial), EncodPulses(_EncodPulses)
+{
+    speedPin.period_ms(2);
+    speedPin.write(0);
+    
+};
+
+
+
+void MotorContinuo::Forward()   { L1=1;  L2=0;}
+void MotorContinuo::Back()      { L1=0;  L2=1;}
+void MotorContinuo::Stop()      { L1=0;  L2=0;}
+void MotorContinuo::StopT()     { L1=1;  L2=1;}
+void MotorContinuo::SpeedDuty(int v) { speedPin.write(float(v/100.0));}
+void MotorContinuo::SpinLength_ms(float t)    { t++;}// Duración del giro en ms
+void MotorContinuo::SpinLength(float t)       { t++;};
+    
+    
+
+///************  MOTOR DISCRETO ********************************//    
+
+/// CONSTRUCTOR
+MotorDiscreto::MotorDiscreto(PinName _Dir, PinName _Step, int _NPasos, PinName _encodin, PinName _PosInicial, int _EncodPulses) :
+Dir(_Dir), Step(_Step), NPasos(_NPasos), encodin(_encodin), PosInicial(_PosInicial), EncodPulses(_EncodPulses)
+{
+};    
+ 
+ 
+ // *************   METODOS ***************** ///
+    
+void MotorDiscreto::moveMotor(void)  
+    {
+        if (StepOnHold != 0 && _moveMotorStopped == false) 
+            {
+                Step = !Step; // Se hace elcambio de estado en el pin Step
+                entradas++; // se registra cada paso efectivo el cual es valido cada 2 entradas 
+                            // 1ra entrada: tiempo en Bajo
+                            // 2da entrada: tiempo en Alto
+                            // Es decir cuando Step cumple un periodo.
+                if (entradas >= 2) // cuando se registran 2 entradas se disminuye un paso
+                {
+                    StepOnHold--; // Se elimina 1 paso de los pendientes
+                    entradas = 0; 
+                }
+                
+                Move.attach(callback(this,&MotorDiscreto::moveMotor), (TStep/2) ); // Reiniciamos el tiempo de imterrupcion
+                
+            }
+        else if (StepOnHold == 0 || _moveMotorStopped == true) // si no hay mas pasos pendientes
+            {
+                Move.detach(); // desabilita la interrupcion
+                entradas = 0;
+            }
+    }
+
+
+void MotorDiscreto::Forward()   { Dir=1;}
+void MotorDiscreto::Back()      { Dir=0;}
+void MotorDiscreto::Stop()      { EnablePin = 0; _moveMotorStopped = true;}
+void MotorDiscreto::StopT()     { Move.detach(); _moveMotorStopped = true;}
+void MotorDiscreto::StepFreq(long n) { StepsBySecond = n; TStep = (1/float(n));}
+void MotorDiscreto::RunStep(long n) { StepOnHold = n; Move.attach(callback(this,&MotorDiscreto::moveMotor), (TStep/2) ); _moveMotorStopped = false; }// Duración del giro en ms
+void MotorDiscreto::Run(float t)    { float Fp = (1/TStep); StepOnHold = long(t*Fp); Move.attach(callback(this,&MotorDiscreto::moveMotor), (TStep/2) ); _moveMotorStopped = false; }
+void MotorDiscreto::RunRound(int n) { StepOnHold = (NPasos * n); Move.attach(callback(this,&MotorDiscreto::moveMotor), (TStep/2) ); _moveMotorStopped = false; }
+long MotorDiscreto::getStepOnHold(void){return StepOnHold; }
+
+void Ustep(int resolucion, DigitalOut* _M0, DigitalOut* _M1, DigitalOut* _M2)
+    {
+        
+        switch(resolucion)
+        {
+            case 1: *_M0 = 0; *_M1 = 0; *_M2 = 0;
+                    break;
+            case 2: *_M0 = 1; *_M1 = 0; *_M2 = 0;
+                    break;
+            case 4: *_M0 = 0; *_M1 = 1; *_M2 = 0;
+                    break; 
+            case 8: *_M0 = 1; *_M1 = 1; *_M2 = 1;
+                    break;
+            case 16: *_M0 = 0; *_M1 = 0; *_M2 = 1;
+                    break;
+            case 32: *_M0 = 1; *_M1 = 0; *_M2 = 1;
+                    break;
+        
+            default: *_M0 = 0; *_M1 = 0; *_M2 = 0;
+        
+        
+        }
+    
+    
+    }
+
+      
+///************  TRACCIONDISCRETA ********************************//    
+
+
+/// ***************** CONSTRUCTOR ********************** ///
+TraccionD::TraccionD(PinName _StepMI, PinName _DirMI, PinName _StepMD, PinName _DirMD, int _NPasos, float _r, float _L ):
+                    StepMI(_StepMI), DirMI(_DirMI), StepMD(_StepMD), DirMD(_DirMD), NPasos(_NPasos), r(_r), L(_L)
+    {
+        // 1. se halla la Relacion(Rl) de distacia entre los dos Radios(r y L)
+            Rl  = (L / r); 
+            
+        };
+
+ // *************   METODOS ***************** ///
+
+void TraccionD::moveMotor(void)  
+    {
+        if (StepOnHold != 0) 
+            {
+            
+                
+                StepMI = !StepMI; // Se hace elcambio de estado en el pin Step para ambos motores
+                StepMD =  StepMI; 
+                
+                entradas++; // se registra cada paso efectivo el cual es valido cada 2 entradas 
+                            // 1ra entrada: tiempo en Bajo
+                            // 2da entrada: tiempo en Alto
+                            // Es decir cuando Step cumple un periodo.
+                if (entradas >= 2) // cuando se registran 2 entradas se disminuye un paso
+                {
+                    StepOnHold--; // Se elimina 1 paso de los pendientes
+                    entradas = 0; 
+                }
+                
+                Move.attach(callback(this,&TraccionD::moveMotor), (TStep/2) ); // Reiniciamos el tiempo de imterrupcion
+                
+            }
+        else if (StepOnHold == 0) // si no hay mas pasos para dar se deshabilita las interrupciones.
+            {
+                Move.detach(); 
+            }
+    }
+
+
+void TraccionD::Forward()   { DirMI=1; DirMD=1;} // Configua de giro de ambos motores el el mismo sentido para avanzar hacia adelante
+void TraccionD::Back()      { DirMI=0; DirMD=0;} // Configua el sentido giro en ambos motores contrario al de Forward(), para avanzar hacia atras
+void TraccionD::Left()      { DirMI=0; DirMD=1;} // Configura el sentido de giro de ambos motores de manera contraria para girar hacia la izquierda
+void TraccionD::Right()     { DirMI=1; DirMD=0;} // Configura el sentido de giro de ambos motores de manera contraria e inverso al de Left() para girar hacia la derecha
+void TraccionD::Stop()      { EnablePinM1 = 0; EnablePinM2 = 0;}
+void TraccionD::StopT()     { Move.detach();}
+void TraccionD::StepFreq(long n) { StepsBySecond = n; TStep = (1/float(n));}
+void TraccionD::RunStep(long n){ StepOnHold = n; Move.attach(callback(this,&TraccionD::moveMotor), (TStep/2) ); }// Duración del giro en ms
+void TraccionD::Run(float t)    { float Fp = (1/TStep); StepOnHold = long(t*Fp); Move.attach(callback(this,&TraccionD::moveMotor), (TStep/2) ); }
+void TraccionD::RunRound(int n) { StepOnHold = (NPasos * n); Move.attach(callback(this,&TraccionD::moveMotor), (TStep/2) ); }
+long TraccionD::getStepOnHold(void){return StepOnHold; }
+
+void TraccionD::Giro(long grados, bool sentido)     
+{ 
+    
+    StepOnHold = grados * int(Rl * NPasos);
+    StepOnHold /= 360; 
+    if(sentido == true) Right(); else if (sentido == false) Left();
+    Move.attach(callback(this,&TraccionD::moveMotor), (TStep/2) );
+
+}
+
+
+
+
+
+
+
+
+
+
+