PROCESADORES - 2016-03. TAREA 2. PID+IrDA

Dependencies:   Pulse1 TextLCD mbed

Fork of PID_ENCODER_OK by Gustavo Ramirez

Tarea 2: IRDA + PID

PROCESADORES - 2016-03

Por:

  • Jaime Alonso Osorio Palacio
  • David Fuertes Chaguezac
  • Wilson Anibal Ortega Andrade
  • John Wilmer Ruiz López

    A partir del código de PID+ENCODER: https://developer.mbed.org/users/tony63/code/PID_ENCODER_OK/ , se adiciona un sensor IrDA (Infrared Data Association) para programar a través de este los parámetros del PID (spnum, kp, ki y kd) en la FRDM-KL25Z. Observar todos estos datos y configuraciones en una LCD. Posee depuración via USB en una terminal (se usó Termite 3.2.) para conocer los estados en los que se encuentra el programa y verificar los datos.
    IMÁGENES:

Files at this revision

API Documentation at this revision

Comitter:
jaosoriop
Date:
Wed Nov 23 00:49:51 2016 +0000
Parent:
1:058b8f5c135d
Commit message:
PID + IRDA

Changed in this revision

Pulse1.lib Show annotated file Show diff for this revision Revisions of this file
QEI.lib Show diff for this revision Revisions of this file
main.cpp Show annotated file Show diff for this revision Revisions of this file
diff -r 058b8f5c135d -r fe2c4b1f132f Pulse1.lib
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Pulse1.lib	Wed Nov 23 00:49:51 2016 +0000
@@ -0,0 +1,1 @@
+http://mbed.org/users/tony63/code/Pulse1/#48651f86a80c
diff -r 058b8f5c135d -r fe2c4b1f132f QEI.lib
--- a/QEI.lib	Sun Apr 24 18:32:52 2016 +0000
+++ /dev/null	Thu Jan 01 00:00:00 1970 +0000
@@ -1,1 +0,0 @@
-http://mbed.org/users/aberk/code/QEI/#5c2ad81551aa
diff -r 058b8f5c135d -r fe2c4b1f132f main.cpp
--- a/main.cpp	Sun Apr 24 18:32:52 2016 +0000
+++ b/main.cpp	Wed Nov 23 00:49:51 2016 +0000
@@ -1,9 +1,32 @@
-#include "mbed.h"
-#include "QEI.h"
-#include "TextLCD.h"
+/*
+PROCESADORES - 2016-03
+TAREA 2.  
+    A partir del código de PID+TECLADO, utilizar un sensor IRDA para programar los 
+    parámetros del PID (spnum, kp, ki y kd) en la FRDM-KL25Z. Observar todos estos 
+    datos y configuraciones en una LCD
+PRESENTADO POR:
+    Jaime Alonso Osorio Palacio
+    David Fuertes Chaguezac         
+    Wilson Anibal Ortega Andrade
+    John Wilmer Ruiz López
+*/
+
+#include "mbed.h" 
+#include "TextLCD.h"    // LCD 
+#include <Pulse1.h>
+#include "math.h" 
+#include "stdio.h"      //printf, etc
+#include "string.h"
+#include "stdlib.h"     // atoi
+#include "stdint.h"
+#include <assert.h>
+
+//****************** CONFIGURACIÓN DE PUERTOS DE COMUNICACIÓN ******************
+
+PulseInOut irda(PTD0);// en este puerto se pone el sensor infrarrojo
+Serial pc(USBTX, USBRX);        //configuro puerto serial
 
 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
@@ -11,32 +34,65 @@
 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
+//********************************* PARÁMETROS *********************************
 
-
-//codigos movimiento del curzor
-
+//codigos movimiento del cursor
 //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;
 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 i=0,ii=0;
+int numero;
+char tecla1[1], tecla2[1],tecla3[1];
+int valor1=0, valor2=0, valor3=0;
+int valornum=0;
+int flag1=0, flag2=0, flag3=0;
+int conteo=0;
 
-int main()
-{
+//****************************** DATOS CONTROL IR ******************************
+
+const int head_H = 2880;    //+20% medida con osciloscopio en microsegundos
+const int head_L = 1920;    //-20%  medida con osciloscopio
+const int T_alto=567;       //ponga su tiempo de la prueba
+const int T_bajo=1170;      //ponga su tiempo de la prueba
+const int num_bits = 21;    //ponga su numero de bits
+int header =0;              //tiempo de cabecera pulso abajo
+int num[num_bits];          //cadena para almacenar todos los tiempos que conforman los bits de datos
+int aux[21];                //variable donde se concatenarán la trama de "bits"
+int binM[20];               // arreglo para dar valor a cada bit en decimal
+int dato;                   //tiempo de cada dato que se lee
+
+// DATOS DE PRUEBA CONTROL SONY RM-Y173 (SIRVE PARA SONY TRINITRON KV-21ME42/8)
+int uno=4224;       int UNO[]   ={0,0,0,0,0,0,0,1,0,0,0,0,1,0,0,0,0,0,0,0};
+int dos=12417;      int DOS[]   ={1,0,0,0,0,0,0,1,0,0,0,0,1,1,0,0,0,0,0,0};
+int tres=20610;     int TRES[]  ={0,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0};
+int cuatro=28803;   int CUATRO[]={0,1,0,0,0,0,0,1,0,0,0,0,1,0,1,0,0,0,0,0};
+int cinco=36996;    int CINCO[] ={0,0,1,0,0,0,0,1,0,0,0,0,1,0,0,1,0,0,0,0};
+int seis=45189;     int SEIS[]  ={1,0,1,0,0,0,0,1,0,0,0,0,1,1,0,1,0,0,0,0};
+int siete=53382;    int SIETE[] ={0,1,1,0,0,0,0,1,0,0,0,0,1,0,1,1,0,0,0,0};
+int ocho=61575;     int OCHO[]  ={1,1,1,0,0,0,0,1,0,0,0,0,1,1,1,1,0,0,0,0};
+int nueve=69768;    int NUEVE[] ={0,0,0,1,0,0,0,1,0,0,0,0,1,0,0,0,1,0,0,0};
+int cero=77961;     int CERO[]  ={1,0,0,1,0,0,0,1,0,0,0,0,1,1,0,0,1,0,0,0};
+int power=176277;   int POWER[] ={1,0,1,0,1,0,0,1,0,0,0,0,1,1,0,1,0,1,0,0};
+int enter=94347;    int ENTER[] ={1,1,0,1,0,0,0,1,0,0,0,0,1,1,1,0,1,0,0,0};
+
+//******************************************************************************
+//******************************* CICLO PRINCIPAL ******************************
+//******************************************************************************
+
+int main(){
     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.locate(8,0);                // necesariamente (columna, fila)
     lcd.printf("Kp=%d",kpnum);
     lcd.locate(0,1);
     lcd.printf("Ki=%d",kinum);
@@ -44,16 +100,216 @@
     lcd.printf("Kd=%d",kdnum);
     lcd.locate(0,0);
     lcd.printf("Sp=%d",spnum);
+    
+    binM[0]=1;      // se crea un arreglo con los valores de cada bit en decimal
+    for(i=1;i<(num_bits-1);++i){
+        binM[i]=binM[i-1]*2;   }   // printf("%i",aux[i]);     
+    
+    while(1) { 
+    diferencia=0, conteo=0; valor1=0, valor2=0, valor3=0;
+    char valor[10] = {0};  strcpy(tecla1, ""); strcpy(tecla2, ""); strcpy(tecla3, "");
+ini1: 
+        int header=0;
+        led2=1;
+        led1=1;
+        header = irda.read_low_us();    //funcion para leer un pulso de caida o bajo
+        if (header > head_L && header < head_H) goto seguir1;//verificar que este en la tolerancia +-20%
+        else goto ini1;
+seguir1:
+        wait_us(333);         //duración aproximada de tiempo muerto antes de comenzar la trama
+        led2=0;               //enciendo un LED para indicar que pasó el header y ya se van a recibir datos
+        for(i=0;i<(num_bits-1);++i){ // POR OSCILOSCOPIO se determina que llegan (num_bits),datos
+            dato = irda.read_low_us(); //leer un bit de datos que es pulso bajo en este control
+            num[i]=dato;      //guarda cada dato en el arreglo num
+            wait_us(333);   
+        }
+        
+        /*
+        wait(0.1); //espero un poquito antes de leer todo el arreglo y ponerlo en pantalla 
+        pc.printf("Duracion de cabecera = %d\n", header);
+        pc.printf("Duracion de cada bit de llegada=");
+        for(i=0;i<(num_bits-1);++i){
+            pc.printf("%d,",num[i]);
+        }
+        wait(0.1);  //espero e imprimo en binario 
+        pc.printf("\n");
+        pc.printf("En binario =");
+        */
+        for(i=0;i<(num_bits-1);++i){
+            if(num[i] > ((T_alto+T_bajo)/2)){
+                pc.printf("1");
+                aux[i]=1;
+            }
+            else{
+                pc.printf("0");
+                aux[i]=0;
+            }
+        }
+        // strcpy(tecla, "");
+        // printf("\t\t\t Tecla presionada: %s\n",tecla);
+        
+        // convierto a decimal la tecla presionada
+        numero=0;
+        for(i=0;i<(num_bits-1);++i){
+            numero=numero+(binM[i]*aux[i]);
+        }
+        // printf("\n");
+        // printf("Convertido a decimal=%d \n",numero);
 
-    while(1)
-    {
-        //lcd.locate(8,0);
-        //lcd.printf("Kp=%d",encoder.getPulses());
-        //wait(.5);
-
-        diferencia=encoder.getPulses()-cambio;
-        cambio=encoder.getPulses();
-
+        if      (numero==uno)   {strcpy(tecla1, "1");}
+        else if (numero==dos)   {strcpy(tecla1, "2");}
+        else if (numero==tres)  {strcpy(tecla1, "3");}
+        else if (numero==cuatro){strcpy(tecla1, "4");}
+        else if (numero==cinco) {strcpy(tecla1, "5");}
+        else if (numero==seis)  {strcpy(tecla1, "6");}
+        else if (numero==siete) {strcpy(tecla1, "7");}
+        else if (numero==ocho)  {strcpy(tecla1, "8");}
+        else if (numero==nueve) {strcpy(tecla1, "9");}
+        else if (numero==cero)  {strcpy(tecla1, "0");}
+        else if (numero==power) {strcpy(tecla1, "P");}
+        else if (numero==enter) {strcpy(tecla1, "E");}
+        else {goto ini1;}
+        pc.printf("\t\t\t Tecla presionada: %s\n",tecla1);
+        valor1=100*atoi(tecla1);
+        
+CONTEO:
+        conteo++;
+        
+        if (conteo == 1) {
+            if (strcmp(tecla1, "P")!=0){
+                if (strcmp(tecla1, "E")!=0){
+                    // strcpy(valor,tecla1);
+                    pc.printf("VALOR en conteo=1 es %s \n",valor);
+ini2:               header=0; led2=1; led1=1;
+                    header = irda.read_low_us();    //funcion para leer un pulso de caida o bajo
+                    if (header > head_L && header < head_H) goto seguir2;//verificar que este en la tolerancia +-20%
+                    else goto ini2;
+seguir2:            wait_us(333);         //duración aproximada de tiempo muerto antes de comenzar la trama
+                    led2=0;               //enciendo un LED para indicar que pasó el header y ya se van a recibir datos
+                    for(i=0;i<(num_bits-1);++i){ // POR OSCILOSCOPIO se determina que llegan (num_bits),datos
+                        dato = irda.read_low_us(); //leer un bit de datos que es pulso bajo en este control
+                        num[i]=dato;      //guarda cada dato en el arreglo num
+                        wait_us(333);   
+                    }
+                    
+                    for(i=0;i<(num_bits-1);++i){
+                        if(num[i] > ((T_alto+T_bajo)/2)){
+                            pc.printf("1");
+                            aux[i]=1;
+                        }
+                        else{
+                            pc.printf("0");
+                            aux[i]=0;
+                        }
+                    }
+                    
+                    // convierto a decimal la tecla presionada
+                    numero=0;
+                    for(i=0;i<(num_bits-1);++i){
+                        numero=numero+(binM[i]*aux[i]);
+                    }
+                    // printf("\n");
+                    // printf("Convertido a decimal=%d \n",numero);
+            
+                    if      (numero==uno)   {strcpy(tecla2, "1");}
+                    else if (numero==dos)   {strcpy(tecla2, "2");}
+                    else if (numero==tres)  {strcpy(tecla2, "3");}
+                    else if (numero==cuatro){strcpy(tecla2, "4");}
+                    else if (numero==cinco) {strcpy(tecla2, "5");}
+                    else if (numero==seis)  {strcpy(tecla2, "6");}
+                    else if (numero==siete) {strcpy(tecla2, "7");}
+                    else if (numero==ocho)  {strcpy(tecla2, "8");}
+                    else if (numero==nueve) {strcpy(tecla2, "9");}
+                    else if (numero==cero)  {strcpy(tecla2, "0");}
+                    else if (numero==power) {strcpy(tecla2, "P");}
+                    else if (numero==enter) {strcpy(tecla2, "E");}
+                    else {goto ini2;}
+                    pc.printf("\t\t\t Tecla presionada: %s\n",tecla2);
+                    valor2=10*atoi(tecla2);
+                    goto    CONTEO;
+                    
+                } //if (strcmp(tecla1, "E")!=0){
+                else if(strcmp(tecla1, "E")==0){
+                    {diferencia = valor1; goto siguiente;}
+                }
+            }  //if (strcmp(tecla1, "P")!=0){
+        }  //if (conteo == 1) {
+////////////////////////////////////////////////////////////////////////////////
+        if (conteo == 2) {
+            if (strcmp(tecla2, "P")!=0){
+                if (strcmp(tecla2, "E")!=0){
+                    // strcpy(valor,tecla2);
+ini3:               header=0; led2=1; led1=1;
+                    header = irda.read_low_us();    //funcion para leer un pulso de caida o bajo
+                    if (header > head_L && header < head_H) goto seguir3;//verificar que este en la tolerancia +-20%
+                    else goto ini3;
+seguir3:            wait_us(333);         //duración aproximada de tiempo muerto antes de comenzar la trama
+                    led2=0;               //enciendo un LED para indicar que pasó el header y ya se van a recibir datos
+                    for(i=0;i<(num_bits-1);++i){ // POR OSCILOSCOPIO se determina que llegan (num_bits),datos
+                        dato = irda.read_low_us(); //leer un bit de datos que es pulso bajo en este control
+                        num[i]=dato;      //guarda cada dato en el arreglo num
+                        wait_us(333);   
+                    }
+                    
+                    for(i=0;i<(num_bits-1);++i){
+                        if(num[i] > ((T_alto+T_bajo)/2)){
+                            pc.printf("1");
+                            aux[i]=1;
+                        }
+                        else{
+                            pc.printf("0");
+                            aux[i]=0;
+                        }
+                    }
+                    
+                    // convierto a decimal la tecla presionada
+                    numero=0;
+                    for(i=0;i<(num_bits-1);++i){
+                        numero=numero+(binM[i]*aux[i]);
+                    }
+                    // printf("\n");
+                    // printf("Convertido a decimal=%d \n",numero);
+            
+                    if      (numero==uno)   {strcpy(tecla3, "1");}
+                    else if (numero==dos)   {strcpy(tecla3, "2");}
+                    else if (numero==tres)  {strcpy(tecla3, "3");}
+                    else if (numero==cuatro){strcpy(tecla3, "4");}
+                    else if (numero==cinco) {strcpy(tecla3, "5");}
+                    else if (numero==seis)  {strcpy(tecla3, "6");}
+                    else if (numero==siete) {strcpy(tecla3, "7");}
+                    else if (numero==ocho)  {strcpy(tecla3, "8");}
+                    else if (numero==nueve) {strcpy(tecla3, "9");}
+                    else if (numero==cero)  {strcpy(tecla3, "0");}
+                    else if (numero==power) {strcpy(tecla3, "P");}
+                    else if (numero==enter) {strcpy(tecla3, "E");}
+                    else {goto ini3;}
+                    pc.printf("\t\t\t Tecla presionada: %s\n",tecla3);
+                    valor3=1*atoi(tecla3);
+                    goto    CONTEO;
+                } //if (strcmp(tecla2, "E")!=0){
+                else if(strcmp(tecla2, "E")==0){
+                    {goto siguiente;}
+                }
+            }  //if (strcmp(tecla1, "P")!=0){
+        }  //if (conteo == 1) {
+////////////////////////////////////////////////////////////////////////////////
+        if (conteo == 3){
+            goto siguiente;
+        }
+    
+ siguiente:       
+        
+        // diferencia=encoder.getPulses()-cambio;
+        // cambio=encoder.getPulses();
+        
+        diferencia=valor1+valor2+valor3;
+        
+        if (strcmp(tecla1, "P")==0) 
+        {
+            pc.printf("Comienza el PID por presionar POWER");
+            break;     // si se presiona el botón POWER se sale de la configuración y comienza el PID
+        }
+        
         if (diferencia==0)
         {
             //nada
@@ -62,7 +318,7 @@
         {
             if(pos==1)
             {
-                if(spnum+diferencia>=999)
+                if(diferencia>=999)
                 {
                     spnum=999;
                     lcd.locate(3,0);
@@ -72,14 +328,14 @@
                 }
                 else
                 {
-                    spnum+=diferencia;
+                    spnum=diferencia;
                     lcd.locate(3,0);
                     lcd.printf("%d", spnum);
                 }
-            }
+            } //else if(pos==1)
             else if(pos==2)
             {
-                if(kpnum+diferencia>=999)
+                if(diferencia>=999)
                 {
                     kpnum=999;
                     lcd.locate(11,0);
@@ -89,14 +345,14 @@
                 }
                 else
                 {
-                    kpnum+=diferencia;
+                    kpnum=diferencia;
                     lcd.locate(11,0);
                     lcd.printf("%d", kpnum);
                 }
-            }
+            } //else if(pos==2)
             else if(pos==3)
             {
-                if(kinum+diferencia>=999)
+                if(diferencia>=999)
                 {
                     kinum=999;
                     lcd.locate(3,1);
@@ -106,14 +362,14 @@
                 }
                 else
                 {
-                    kinum+=diferencia;
+                    kinum=diferencia;
                     lcd.locate(3,1);
                     lcd.printf("%d", kinum);
                 }
-            }
+            } //else if(pos==3)
             else if(pos==4)
             {
-                if(kdnum+diferencia>=999)
+                if(diferencia>=999)
                 {
                     kdnum=999;
                     lcd.locate(11,1);
@@ -123,79 +379,17 @@
                 }
                 else
                 {
-                    kdnum+=diferencia;
+                    kdnum=diferencia;
                     lcd.locate(11,1);
                     lcd.printf("%d", kdnum);
                 }
-            }
-        }
+            }   //else if(pos==4)
+        } // else if(diferencia>0)
         
-        else if(diferencia<0)
+
+        if (strcmp(tecla1, "E")==0)  //cambia la posicion de ingreso de parametros si se presiona en botón ENTER
         {
-            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
-        {
+            pc.printf("Cambio de posicion por presionar ENTER");
             led3 =!led3;
             if(pos==4)
             {
@@ -223,12 +417,9 @@
             }
             wait(0.25);
 
-        }
+        } //if (strcpy(tecla, "E")==0)
 
-        if (!button4)
-        {
-            break;     //sale del bucle si pisan suiche4
-        }
+
         wait(0.1);        
     }
 
@@ -260,45 +451,26 @@
         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;
-        }
-
+        if(pid<=0) {
+            pid=0; }
         // se verifica que pid sea menor o igual la valor maximo *****************
-        if (pid > 999)
-        {
-            pid=999;
-        }
-
-       
+        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);
+            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) **************
+        u.write(o);    //  se envia el valor pid a puerto analogico de salida (D/A) **************
         
         //  se repite el ciclo
         wait_ms(300);