Tarea-1-Procesadores-2016-2

Dependencies:   QEI TextLCD mbed

Fork of PID by Team La Verga

main.cpp

Committer:
LaVerga
Date:
2016-10-27
Revision:
0:8ce5f8fa8f9b
Child:
1:e1360b8db5e0

File content as of revision 0:8ce5f8fa8f9b:

#include "mbed.h"
#include "QEI.h"
#include "TextLCD.h"
#include "stdio.h"
#include "string.h"

Serial pc(USBTX,USBRX); //puertos del PC
TextLCD lcd(PTB10, PTB11, PTE2, PTE3, PTE4, PTE5); // rs, e, d4-d7
QEI encoder (PTA13, PTD5, NC, 624);
AnalogIn y(PTB3);//entrada analoga
AnalogOut u(PTE30);//salida analoga OJO solo se le pueden drenar 1.5mA en circuitos use un Buffer
//si se ignora esto se arruina la FRDMKL25Z
DigitalOut led1(LED1);
DigitalOut led2(LED2);
DigitalOut led3(LED3);

DigitalIn button3(PTC16);//cambia ingreso de los 4 parametros
DigitalIn button4(PTC17);//termina y consolida valores de 4 parametros y sale del loop

//int C1=0x0E; // solo muestra el curzor
int C2=0x18; // desplaza izquierda
int C3=0x1A; // desplaza derecha
int C4=0x0C; // quito cursor bajo

int C1=0x0F;
char buffer[6];// TAMAÑO DEL BUFER
char cadena[3];
Timer t;   //VALOR DEL TIEMPO
int count;
int i = 0;
int c=0;
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,num=0,pos=1;
 
int readBuffer(char *buffer,int count)   //esta funcion lee un bufer de datos
{
    int i=0; 
    t.start();    //CUENTA EL TIEMPO DE CONEXION E INICIA
    while(1) {
        while (pc.readable()) {
            char c = pc.getc();
            //if (c == '\r' || c == '\n') c = '$';//si se envia fin de linea o de caracxter inserta $
            buffer[i++] = c;//mete al bufer el caracter leido
            if(i > count)break;//sale del loop si ya detecto terminacion
        }
        if(i > count)break;
        if(t.read() > 1) {  //MAS DE UN SEGUNDO DE ESPERA SE SALE Y REINICA EL RELOJ Y SE SALE
            t.stop();
            t.reset();
            break;
        }
    }
     return 0;
}

void cleanBuffer(char *buffer, int count)  //esta funcion limpia el bufer
{
    for(int i=0; i < count; i++) {
        buffer[i] = '\0';
    }
}

void LecturaSerial(void){
    /***********
    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){
       if (pc.readable()) {
          readBuffer(buffer,6);
          wait(0.2);
          pc.printf("%s\n",buffer);  //imprime el bufer
          
          cadena[0]=buffer[2]; 
          cadena[1]=buffer[3];
          cadena[2]=buffer[4];
          num=strtod(cadena,NULL);
          if(num>999){
              num=999;
              }
          if(num<0){
              num=0;
              }
          
          if (buffer[0]=='S' && buffer[1]=='P'){
            spnum=num;
            lcd.locate(3,0);
            lcd.printf("    ");
            lcd.locate(3,0);
            lcd.printf("%d", spnum);
            
              }
          
          if (buffer[0]=='K' && buffer[1]=='P'){
            kpnum=num;
            lcd.locate(11,0);
            lcd.printf("    ");
            lcd.locate(11,0);
            lcd.printf("%d", kpnum);
              }
          
          if (buffer[0]=='K' && buffer[1]=='I'){
            kinum=num;
            lcd.locate(3,1);
            lcd.printf("    ");
            lcd.locate(3,1);
            lcd.printf("%d", kinum);
              }
          
          if (buffer[0]=='K' && buffer[1]=='D'){
            kdnum=num;
            lcd.locate(11,1);
            lcd.printf("    ");
            lcd.locate(11,1);
            lcd.printf("%d", kdnum);
            }
            
            if(buffer[0]=='X'){ //Vuelve a darle dominio al encoder.
            break;
            }
            
          cleanBuffer(buffer,6);
            
          } //Cierra el pc.readable()
          
                          
}//Cierre while(1)

/*********
//    lcd.writeCommand(C4);//escribimos un comando segun 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=%3.0f",spnum);
    lcd.locate(8,1);
    lcd.printf("Co=%3.0f",pid);
    wait(1);

// CICLO PRINCIPAL CONTROLADOR PID
 lop2:  med = y.read()*999;
        err = (spnum-med);  //se calcula el error
        ap = kpnum*err*0.01f;     //se calcula la accion proporcinal
        ai =(kinum*err*0.01f)+ai;    //calculo de la integral del error
        ad = kdnum*(err-err_v)*0.01f; //calculo de la accion derivativa
        pid = (ap+ai+ad);
        // se verifica que pid sea positivo **************************************
        if(pid<=0)
        {
            pid=0;
        }

        // se verifica que pid sea menor o igual la valor maximo *****************
        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);
           
            
        

        //Normalizacion de la salida
        // se actualizan las variables *******************************************
        err_v = err;
        o = pid/999;
        u.write(o);
        //  se envia el valor pid a puerto analogico de salida (D/A) **************
        
        //  se repite el ciclo
        wait_ms(300);
        goto lop2;
        ********/
    }

int main(void) //**********************************MAIN***************************************************
       { 
       pc.baud(9600);
       pc.format(8,Serial::None,1);
       lcd.locate(0,1);
       lcd.printf("**Control PID**");
       wait(2);
       lcd.cls(); // Borrar Pantalla
       lcd.writeCommand(C1);//escribimos un comando segun el manual del modulo 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 (!button3)  //cambia la posicion de ingreso de parametros
        {
            led3 =!led3;
            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 (!button4)
        {
            break;     //sale del bucle si pisan suiche4
        }
        wait(0.1);        
       
       if(pc.readable()){       //Si hay algo para leer entra al bucle de lectura serial y da todo el dominio al serial.
       readBuffer(buffer,6);
           if(buffer[0]=='G'){               
               break;      //sale del bucle si le dan al botón guardar del celular.
               }
               else{
                   LecturaSerial();
                   readBuffer(buffer,6);
                   wait(0.2);
                   }
           }
           
           }
                      
//Transicion
    lcd.writeCommand(C4);//escribimos un comando segun 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=%3.0f",spnum);
    lcd.locate(8,1);
    lcd.printf("Co=%3.0f",pid);
    wait(1);

// CICLO PRINCIPAL CONTROLADOR PID
 lop1:  med = y.read()*999;
        err = (spnum-med);  //se calcula el error
        ap = kpnum*err*0.01f;     //se calcula la accion proporcinal
        ai =(kinum*err*0.01f)+ai;    //calculo de la integral del error
        ad = kdnum*(err-err_v)*0.01f; //calculo de la accion derivativa
        pid = (ap+ai+ad);
        // se verifica que pid sea positivo **************************************
        if(pid<=0)
        {
            pid=0;
        }

        // se verifica que pid sea menor o igual la valor maximo *****************
        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);
           
            
        

        //Normalizacion de la salida
        // se actualizan las variables *******************************************
        err_v = err;
        o = pid/999;
        u.write(o);
        //  se envia el valor pid a puerto analogico de salida (D/A) **************
        
        pc.printf("%3.0f\t",err);
        pc.printf("%3.0f\t",med);
        pc.printf("%3.0f\t",spnum);
        pc.printf("%3.0f\n",pid);
        
        //  se repite el ciclo
        wait_ms(300);
        goto lop1;

}//Cierre main