Uso de la clase Motor para el control de velocidad de un motor continuo con encoder.

Dependencies:   mbed

Revision:
0:75421f27540e
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Motor.cpp	Fri Sep 03 05:04:12 2021 +0000
@@ -0,0 +1,113 @@
+#include "mbed.h"
+#include "Motor.h"
+
+
+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++;};
+    
+
+
+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)
+{
+    
+    
+
+};    
+    
+void MotorDiscreto::moveMotor(void)  
+    {
+        if (StepOnHold != 0) 
+            {
+                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)
+            {
+                Move.detach();
+            }
+    }
+
+
+void MotorDiscreto::Forward()   { Dir=1;}
+void MotorDiscreto::Back()      { Dir=0;}
+void MotorDiscreto::Stop()      { EnablePin = 0; }
+void MotorDiscreto::StopT()     { Move.detach();}
+void MotorDiscreto::StepFreq(int n) { StepsBySecond = n; TStep = (1/n);}
+void MotorDiscreto::RunStep(long n){ StepOnHold = n; Move.attach(callback(this,&MotorDiscreto::moveMotor), (TStep/2) ); }// Duración del giro en ms
+void MotorDiscreto::Run(float t)    { StepOnHold = long(t/TStep); Move.attach(callback(this,&MotorDiscreto::moveMotor), (TStep/2) ); }
+void MotorDiscreto::RunRound(int n) { StepOnHold = (NPasos * n); Move.attach(callback(this,&MotorDiscreto::moveMotor), (TStep/2) ); }
+
+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;
+        
+        
+        }
+    
+    
+    }
+        
+    
+ /*   
+void scolor_TCS3200::SetMode(uint8_t mode) {
+    switch (mode){
+        case SCALE_100:  _s0= 1; _s1=1; break;
+        case SCALE_20:   _s0=1 ; _s1=0; break;
+        case SCALE_2:    _s0=0 ; _s1=1; break;
+        case POWER_DOWN: _s0=0 ; _s1=0; break;
+    } 
+};
+ 
+ 
+long  scolor_TCS3200::pulsewidth() {
+    while(!_s_in);
+    timer.start();
+    while(_s_in);
+    timer.stop();
+    float pulsewidth_v = timer.read_us();
+    timer.reset();
+    return pulsewidth_v;
+};
+*/          
+