Para una tarjeta STM32F103C8T6, PID con un encoder para modificación de parametros.

Dependencies:   mbed QEI DebouncedIn TextLCD

main.cpp

Committer:
lmrinconp
Date:
2019-07-01
Revision:
0:4185ca92d537

File content as of revision 0:4185ca92d537:

#include "mbed.h"
#include "QEI.h"
#include "TextLCD.h"
#include "DebouncedIn.h"
 
TextLCD lcd(PA_8, PA_9, PA_11, PA_12, PA_15, PB_3);// Declaración de los puertos
QEI encoder (PA_7, PA_6, NC, 624); // (DT, Clk)
AnalogIn vo(PA_0); //entrada análoga
PwmOut vi(PA_1); //salida análoga 

DigitalOut myled(PC_13);  //Activando el led de la tarjeta

DigitalIn mybuttonE(PC_14); //cambia ingreso de  los 4 parámetros (Encoder)
DigitalIn mybutton(PC_15); //termina y consolida valores de 4 parámetros y sale del loop (Pulsador)
 
int cambio=0, diferencia=0;
float pid,o,ai,ad,ap,med,err;
float err_v;
int spnum=0,kinum=0,kpnum=0,kdnum=0,pos=1;
 
int main()
{
    
    lcd.locate(0,0);
    lcd.printf("     Tarea2");     //Título del proyecto
    lcd.locate(0,1);
    lcd.printf("Controlador PID"); //Título del proyecto
    wait(4);
    lcd.cls(); // Borrar Pantalla
   // lcd.writeCommand(C1);//escribimos un comando según el manual del módulo LCD
 
    lcd.locate(8,0);
    lcd.printf("Kp=%d",kpnum);
    lcd.locate(0,1);
    lcd.printf("Ki=%d",kinum);
    lcd.locate(8,1);
    lcd.printf("Kd=%d",kdnum);
    lcd.locate(0,0);
    lcd.printf("Sp=%d",spnum);
 
    while(1)
    {
         
        diferencia=encoder.getPulses()-cambio;
        cambio=encoder.getPulses();
 
        if (diferencia==0)
        {
            //nada
        }
        else if(diferencia>0)
        {
            if(pos==1)
            {
                if(spnum+diferencia>=999)
                {
                    spnum=999;
                    lcd.locate(3,0);
                    lcd.printf("    ");
                    lcd.locate(3,0);
                    lcd.printf("%d", spnum);
                }
                else
                {
                    spnum+=diferencia;
                    lcd.locate(3,0);
                    lcd.printf("%d", spnum);
                }
            }
            else if(pos==2)
            {
                if(kpnum+diferencia>=999)
                {
                    kpnum=999;
                    lcd.locate(11,0);
                    lcd.printf("    ");
                    lcd.locate(11,0);
                    lcd.printf("%d", kpnum);
                }
                else
                {
                    kpnum+=diferencia;
                    lcd.locate(11,0);
                    lcd.printf("%d", kpnum);
                }
            }
            else if(pos==3)
            {
                if(kinum+diferencia>=999)
                {
                    kinum=999;
                    lcd.locate(3,1);
                    lcd.printf("    ");
                    lcd.locate(3,1);
                    lcd.printf("%d", kinum);
                }
                else
                {
                    kinum+=diferencia;
                    lcd.locate(3,1);
                    lcd.printf("%d", kinum);
                }
            }
            else if(pos==4)
            {
                if(kdnum+diferencia>=999)
                {
                    kdnum=999;
                    lcd.locate(11,1);
                    lcd.printf("    ");
                    lcd.locate(11,1);
                    lcd.printf("%d", kdnum);
                }
                else
                {
                    kdnum+=diferencia;
                    lcd.locate(11,1);
                    lcd.printf("%d", kdnum);
                }
            }
        }
        
        else if(diferencia<0)
        {
            if(pos==1)
            {
                if(spnum+diferencia<0)
                {
                    //No ocurre nada
                }
                else
                {
                    spnum+=diferencia;
                    lcd.locate(3,0);
                    lcd.printf("    ");
                    lcd.locate(3,0);
                    lcd.printf("%d", spnum);
                }
            }
            else if(pos==2)
            {
                if(kpnum+diferencia<0)
                {
                    //No ocurre nada
                }
                else
                {
                    kpnum+=diferencia;
                    lcd.locate(11,0);
                    lcd.printf("    ");
                    lcd.locate(11,0);
                    lcd.printf("%d", kpnum);
                }
            }
            else if(pos==3)
            {
                if(kinum+diferencia<0)
                {
                    //No ocurre nada
                }
                else
                {
                    kinum+=diferencia;
                    lcd.locate(3,1);
                    lcd.printf("    ");
                    lcd.locate(3,1);
                    lcd.printf("%d", kinum);
                }
            }
            else if(pos==4)
            {
                if(kdnum+diferencia<0)
                {
                    //No ocurre nada
                }
                else
                {
                    kdnum+=diferencia;
                    lcd.locate(11,1);
                    lcd.printf("    ");
                    lcd.locate(11,1);
                    lcd.printf("%d", kdnum);
                }
            }
        }
 
        if (mybuttonE == 0)  //cambia la posición de ingreso de parámetros
        {
            myled = !myled;// 
            if(pos==4)
            {
                pos=1;
                lcd.locate(3,0);
                lcd.printf("%d", spnum);
            }
            else if (pos==1)
            {
                pos++;
                lcd.locate(11,0);
                lcd.printf("%d", kpnum);
            }
            else if(pos==2)
            {
                pos++;
                lcd.locate(3,1);
                lcd.printf("%d", kinum);
            }
            else if(pos==3)
            {
                pos++;
                lcd.locate(11,1);
                lcd.printf("%d", kdnum);
            }
            wait(0.25);
 
        }
 
        if (mybutton == 0)
        {
            break;     //sale del bucle si pisan suiche4
        }
        wait(0.1);        
    }
 
 
//Transición
  //  lcd.writeCommand(C4);//escribimos un comando según el manual del modulo LCD para quitar cursor bajo
    lcd.cls(); //borra la pantalla
    lcd.printf("   GUARDADOS!");
    wait(1);
    lcd.cls();
    lcd.printf(" INICIA EL PID");
    wait(1);
// se imprimen los parches del control  *****************************************
    lcd.cls();
    lcd.printf("Er=%3.0f",err);
    lcd.locate(8,0);
    lcd.printf("Me=%3.0f",med);
    lcd.locate(0,1);
    lcd.printf("Sp=%d",spnum);
    lcd.locate(8,1);
    lcd.printf("Co=%3.0f",pid);
    wait(1);
 
// CICLO PRINCIPAL CONTROLADOR PID
 lop1:  med = vo.read()*999;
        err = (spnum-med);  //se calcula el error
        ap = kpnum*err*0.01f;     //se calcula la acción proporcinal
        ai =(kinum*err*0.01f)+ai;    //cálculo de la integral del error
        ad = kdnum*(err-err_v)*0.01f; //cálculo de la acción derivativa
        pid = (ap+ai+ad);
        // se verifica que pid sea positivo **************************************
        if(pid<=0)
        {
            pid=0;
        }
 
        // se verifica que pid sea menor o igual al valor máximo *****************
        if (pid > 999)
        {
            pid=999;
        }
 
       
        //se muestran las variables******************************************
            lcd.locate(3,0);
            lcd.printf("   ");
            lcd.locate(3,0);
            lcd.printf("%3.0f",err);
            lcd.locate(11,0);
            lcd.printf("   ");
            lcd.locate(11,0);
            lcd.printf("%3.0f",med);
            lcd.locate(3,1);
            lcd.printf("   ");
            lcd.locate(3,1);
            lcd.printf("%d",spnum);
            lcd.locate(11,1);
            lcd.printf("   ");
            lcd.locate(11,1);
            lcd.printf("%3.0f",pid);
       
        //Normalización de la salida
        // se actualizan las variables *******************************************
        err_v = err;
        o = pid/999;
        vi.write(o);
        //  se envia el valor pid a puerto analogico de salida (D/A) **************
        
        //  se repite el ciclo
        wait_ms(300);
        goto lop1;
}