Software


Implementé dos programas, uno para Android y otro para el ATMEGA, en realidad esta nueva versión Android no es necesaria (y por ende, el programa para Arduino podría ser más sencillo), las versiones ya desarrolladas -tanto "AutitoBT3" cómo "AutittoBT4"- funcionan perfectamente, ya que la modificación desarrollada en el hardware para leer las revoluciones de los motores no implican modificaciones en la forma de enviar datos desde el teléfono celular o tablet hacia el dispositivo a controlar.

Pero en el proceso de puesta en marcha del programa para el ATMEGA me resultó necesario conocer el estado de los pulsos leídos en ambos motores, en tiempo real, a efectos de encontrar la mejor operación para igualar las velocidades finales de ambas rueda, lo que me llevó a desarrollar las siguientes versiones de software´s.

Software para Android:


En cuanto al desarrollo gráfico de la aplicación, no hay mucho que decir, agregué algunas etiquetas donde mostrar los valores leídos de cuatro variables fundamentales, los valores reales de pulsos PWM aplicados a los motores y los pulsos leídos en las ruedas, el valor de esas cuatro variables serían entonces los datos a recuperar desde el metaboard por medio del módulo BlueTooth.

Y ya en el desarrollo de los bloques que hacen al programa, lo particular es la lectura BlueTooth de los datos en cuestión, lo que se realiza por medio del componente temporizador Reloj1 (Timer1):


Y en el evento Temporizador, si ClienteBluetooth1 se encuentra conectado, entonces asignarle a las cuatro etiquetas en sus propiedades Texto (Caption) las cuatro cadenas de texto leídas de la forma más fácil que encontré, esto es recibir cadenas fijas de tres caracteres. De esta forma solo queda garantizar que las cadenas tengan esa longitud, lo que desarrollé en el programa cargado en el ATMEGA.

En cuanto al programa desarrollado para el metaboard, he aprovechado las características intrínsecas del potente ATMEGA, que gentilmente proporciona dos interrupciones por hardware, y justamente son dos encoders los que agrego al circuito...

Algunos de los muchos sitios con información sobre las interrupciones interesantes:
https://www.arduino.cc/en/Reference/AttachInterrupt
http://www.educachip.com/como-y-por-que-usar-las-interrupciones-en-arduino/
http://robologs.net/2015/01/02/tutorial-de-interrupciones-con-arduino/


A continuación, el software completo:

Software para Arduino o Compatible:

/*
  Control de velocidad de dos motores con:
      Simulación de Volante y Acelerador.

      Corrección de velocidades usando encoders
      y las interrupciones del ATMEGA

  Creado 04/04/16
  prof. VIEGAS BARROS, Victor
*/


#include <NewSoftSerial.h>

const int Ecd_0 = 2;  // Pin de conexión encoder Izquierdo
const int Ecd_1 = 3;  // Pin de conexión encoder Derecho
const int PWM_I = 6;  // Pulso PWM motor Izquierdo
const int MtrI1 = 7;  // Dirección motor Izquierdo
const int MtrI2 = 8;  // Dirección motor Izquierdo
const int RX    = 9;  // BT recepción
const int TX    =10;  // BT transmisión
const int PWM_D =11;  // Pulso PWM motor Derecho
const int MtrD1 =12;  // Dirección motor Derecho
const int MtrD2 =13;  // Dirección motor Derecho

volatile byte Pulsos_1, Pulsos_2; // Nros de impulsos
unsigned long msTranscurridos;    // Contador de milisegundos
int s0, s1, s2, Direccion, Velocidad, Rumbo, Dir_1, Dir_2;
float Aux = 0;

NewSoftSerial Blue(RX, TX);


void ContarPulsos1() { Pulsos_1++; }
void ContarPulsos2() { Pulsos_2++; }

void setup() {
  pinMode(Ecd_0, INPUT );
  pinMode(Ecd_1, INPUT );
  pinMode(PWM_I, OUTPUT);
  pinMode(MtrI1, OUTPUT);
  pinMode(MtrI2, OUTPUT);
  pinMode(RX,    INPUT );
  pinMode(TX,    OUTPUT);
  pinMode(PWM_D, OUTPUT);
  pinMode(MtrD1, OUTPUT);
  pinMode(MtrD2, OUTPUT);
  Blue.begin(9600);
 

  attachInterrupt(0, ContarPulsos1, CHANGE); 
  attachInterrupt(1, ContarPulsos2, CHANGE);

  Pulsos_1        = 0;
  Pulsos_2        = 0;
  msTranscurridos = 0;
  Direccion       = 256;
  Velocidad       = 0;
  Rumbo           = 0;
  Sentido(Rumbo);
}

void loop() {
  if(Blue.available() > 5) {
    s0         = Blue.read();   
    s1         = Blue.read();
    s2         = Blue.read();
    Direccion  = Blue.read() * 2;
    Velocidad  = Blue.read();
    Rumbo      = Blue.read();
    Blue.flush();
    if(s0==86 & s1==66 & s2==118) { 

      Sentido(Rumbo);
      if(Velocidad > 0) {
        if(Direccion >= 256) {
          Dir_2 = Direccion - 256;
          Aux   = Velocidad * 0.003930;
        } else Dir_2 = 0;             
        if(Direccion <= 256) {                              
          Dir_1 = 256 - Direccion;
          Aux   = Velocidad * 0.003917;
        } else Dir_1 = 0;    
      } else {             
         Dir_2 = 0;    
         Dir_1 = 0;  
      }                                                   
      Dir_2 = Velocidad - (Dir_2 * Aux);
      Dir_1 = Velocidad - (Dir_1 * Aux);
    }
  }


  if(millis() - msTranscurridos >= 250) {
    detachInterrupt(0);
    detachInterrupt(1);
    msTranscurridos = millis();
    if(Velocidad > 0 && Direccion > 252 && Direccion < 260) {
     if(Rumbo = 1){
      if(Pulsos_1>Pulsos_2)Dir_2=Dir_2-((Pulsos_1-Pulsos_2));
      if(Pulsos_1<Pulsos_2)Dir_1=Dir_1-((Pulsos_2-Pulsos_1));
     } else {
      if(Pulsos_1>Pulsos_2)Dir_1=Dir_1-((Pulsos_1-Pulsos_2));
      if(Pulsos_1<Pulsos_2)Dir_2=Dir_2-((Pulsos_2-Pulsos_1));
     }

     
     //Límites
     if (Dir_1<(Dir_2 * 0.75)) Dir_1 = Dir_2 * 0.75;
     if (Dir_2<(Dir_1 * 0.75)) Dir_2 = Dir_1 * 0.75;
    }
 
    Blue.print(IntToStr(Dir_2));
    Blue.print(IntToStr(Pulsos_2));
    Blue.print(IntToStr(Dir_1));
    Blue.print(IntToStr(Pulsos_1));
 
    Pulsos_1 = 0;
    Pulsos_2 = 0;
    attachInterrupt(0, ContarPulsos1, CHANGE);
    attachInterrupt(1, ContarPulsos2, CHANGE);
  }    
  if(Dir_1 < 0) Dir_1 = 0; else if(Dir_1 > 255) Dir_1 = 255;
  if(Dir_2 < 0) Dir_2 = 0; else if(Dir_2 > 255) Dir_2 = 255;
  analogWrite(PWM_I, Dir_1);
  analogWrite(PWM_D, Dir_2);
}

String IntToStr(int d) {
  if(d < 0) d = 0; else if(d > 255) d = 255;
 
  String s = d;
 
  if(d < 10) s = "00" + s;
  else
    if(d < 100) s = "0" + s;
 
  if(s.length() > 3) s = "Err";
  return s;
}


void Sentido(int d) { //Sentido de giro de los motores
  switch (d) {
    case 0: digitalWrite(SMt_4, HIGH);
            digitalWrite(SMt_5, LOW);
            digitalWrite(SMt_7, LOW);
            digitalWrite(SMt_8, HIGH);
            break;
    case 1: digitalWrite(SMt_4, LOW);
            digitalWrite(SMt_5, HIGH);
            digitalWrite(SMt_7, HIGH);
            digitalWrite(SMt_8, LOW);
            break;
    case 2: digitalWrite(SMt_4, HIGH);
            digitalWrite(SMt_5, LOW);
            digitalWrite(SMt_7, LOW);
            digitalWrite(SMt_8, HIGH);
            break;
    case 3: digitalWrite(SMt_4, LOW);
            digitalWrite(SMt_5, HIGH);
            digitalWrite(SMt_7, LOW);
            digitalWrite(SMt_8, HIGH);
            break;
    case 4: digitalWrite(SMt_4, LOW);
            digitalWrite(SMt_5, LOW);
            digitalWrite(SMt_7, LOW);
            digitalWrite(SMt_8, LOW);
            break;
    case 5: digitalWrite(SMt_4, HIGH);
            digitalWrite(SMt_5, HIGH);
            digitalWrite(SMt_7, HIGH);
            digitalWrite(SMt_8, HIGH);
            break;
  }
}

En principio, se trata del software ya desarrollado y comentado al que se le agregan las rutinas que se disparan cuando se produce una interrupción, así como las correspondientes instrucciones necesarias para enviar los datos vía BT hacia el dispositivo Android.
Reenumeré los pines, ya que originalmente usaba el pin 3 cómo salida PWM, ahora debo usarla en su función de interrupción, esto implica cambiar de pines varias conexiones:

  const int Ecd_0 = 2;  // Pin de conexión encoder Izquierdo
  const int Ecd_1 = 3;  // Pin de conexión encoder Derecho
  const int PWM_I = 6;  // Pulso PWM motor Izquierdo
  const int MtrI1 = 7;  // Dirección motor Izquierdo
  const int MtrI2 = 8;  // Dirección motor Izquierdo
  const int RX    = 9;  // BT recepción
  const int TX    =10;  // BT transmisión
  const int PWM_D =11;  // Pulso PWM motor Derecho
  const int MtrD1 =12;  // Dirección motor Derecho
  const int MtrD2 =13;  // Dirección motor Derecho


También traté de usar identificadores nemónicos para dichos pines, pecando de exceso probablemente.

En cuanto a las variables de trabajo, solo decir que las que se corresponden a las funciones que se dispararán con las interrupciones deben ser del tipo volatile pues así se requiere en el tratamiento de interrupciones:

  volatile byte Pulsos_1, Pulsos_2; // Nros de impulsos
  unsigned long msTranscurridos;    // Contador de milisegundos
  int s0, s1, s2, Direccion, Velocidad, Rumbo, Dir_1, Dir_2;
  float Aux = 0;


“volatile” indica que la variable definida a continuación solo cambie cuando se produzca una interrupción.

  NewSoftSerial Blue(RX, TX); 

Inmediatamente después, la declaración para acceder al dispositivo BlueTooth, lo cual ya fue oportunamente comentado en entradas anteriores.

  void ContarPulsos1() { Pulsos_1++; }
  void ContarPulsos2() { Pulsos_2++; }


Son las funciones que se dispararán cuando se produzca una u otra interrupción, solo incrementan al contador correspondiente, y he leído por ahí que se recomienda que estas funciones sean lo más chicas y rápidas posibles.

  void setup() {
    pinMode(Ecd_0, INPUT );
    pinMode(Ecd_1, INPUT );
    pinMode(PWM_I, OUTPUT);
    pinMode(MtrI1, OUTPUT);
    pinMode(MtrI2, OUTPUT);
    pinMode(RX,    INPUT );
    pinMode(TX,    OUTPUT);
    pinMode(PWM_D, OUTPUT);
    pinMode(MtrD1, OUTPUT);
    pinMode(MtrD2, OUTPUT);
    Blue.begin(9600);
 

    attachInterrupt(0, ContarPulsos1, CHANGE); 
    attachInterrupt(1, ContarPulsos2, CHANGE);

    Pulsos_1        = 0;
    Pulsos_2        = 0;
    msTranscurridos = 0;
    Direccion       = 256;
    Velocidad       = 0;
    Rumbo           = 0;
    Sentido(Rumbo);
  }


La función setup configura los pines según corresponda sean entradas o salidas, así como la velocidad de comunicación, también inicializa las variables de trabajo y setea la dirección de giro de los motores.

Pero especialmente relaciona las interrupciones con las funciones a realizar así como cuando deben dispararse las respectivas funciones, en las instrucciones:

    attachInterrupt(0, ContarPulsos1, CHANGE); 
    attachInterrupt(1, ContarPulsos2, CHANGE);

En mi caso, cuento pulsos tanto cuando cambia de LOW a HIGH como cuando cambia de HIGH a LOW. La idea es obtener el doble de pulsos para reducir el tiempo de corrección de los PWM´s.

  void loop() {
    if(Blue.available() > 5) {
      s0         = Blue.read();   
      s1         = Blue.read();
      s2         = Blue.read();
      Direccion  = Blue.read() * 2;
      Velocidad  = Blue.read();
      Rumbo      = Blue.read();
      Blue.flush();
      if(s0==86 & s1==66 & s2==118) { 

        Sentido(Rumbo);
        if(Velocidad > 0) {
          if(Direccion >= 256) {
            Dir_2 = Direccion - 256;
            Aux   = Velocidad * 0.003930;
          } else Dir_2 = 0;             
          if(Direccion <= 256) {                              
            Dir_1 = 256 - Direccion;
            Aux   = Velocidad * 0.003917;
          } else Dir_1 = 0;    
        } else {             
          Dir_2 = 0;    
          Dir_1 = 0;  
        }                                                   
        Dir_2 = Velocidad - (Dir_2 * Aux);
        Dir_1 = Velocidad - (Dir_1 * Aux);
      }
    }


La primera parte del cuerpo de la función loop sigue siendo la misma ya comentada para simular el comportamiento del volante y del acelerador.

La segunda parte es la modificación de los pulsos PWM a efectos de igualar las velocidades:

  if(millis() - msTranscurridos >= 250) {
    detachInterrupt(0);
    detachInterrupt(1);
    msTranscurridos = millis();
    if(Velocidad > 0 && Direccion > 252 && Direccion < 260) {
     if(Rumbo = 1) {
      if(Pulsos_1>Pulsos_2)Dir_2=Dir_2-((Pulsos_1-Pulsos_2));
      if(Pulsos_1<Pulsos_2)Dir_1=Dir_1-((Pulsos_2-Pulsos_1));
     } else {
      if(Pulsos_1>Pulsos_2)Dir_1=Dir_1-((Pulsos_1-Pulsos_2));
      if(Pulsos_1<Pulsos_2)Dir_2=Dir_2-((Pulsos_2-Pulsos_1));
     }

     if (Dir_1<(Dir_2 * 0.75)) Dir_1 = Dir_2 * 0.75;
     if (Dir_2<(Dir_1 * 0.75)) Dir_2 = Dir_1 * 0.75;
    }
 
    Blue.print(IntToStr(Dir_2));
    Blue.print(IntToStr(Pulsos_2));
    Blue.print(IntToStr(Dir_1));
    Blue.print(IntToStr(Pulsos_1));
 
    Pulsos_1 = 0;
    Pulsos_2 = 0;
    attachInterrupt(0, ContarPulsos1, CHANGE);
    attachInterrupt(1, ContarPulsos2, CHANGE);
  }    

 

Lo que hago es -básicamente- lo visto en los ejemplos de las páginas consultadas... Cada vez que se cumple cierto tiempo (250 milisegundos), se desactivan las interrupciones, se almacena la cantidad de milisegundos transcurridos para usarlos en el siguiente conteo de 250 ms. y a continuación, aplico "mi" versión de corrección de pulsos PWM. 

Si la variable Velocidad es mayor que cero (si el vehículo está parado no tiene sentido hacer ninguna corrección) y si la variable Direccion se encuentra en un rango cercano al centro de sus posibles valores (256 +- 4) entonces vale aplicar alguna corrección.

La modificación de las velocidades depende de si el vehículo se desplaza en una u otra dirección (avanza o retrocede) y consta de restarle al pulso PWM correspondiente la diferencia entre los contadores de pulsos incrementados en cada interrupción.


 Debo decir que este método me funciona bastante bien, pero es más eficiente en una dirección que en la otra. ¿La causa? estimo que se origina en el hecho de que cuando se produce una interrupción se anula la otra, el micro solo puede atender una interrupción por vez, lo que evidentemente provoca que los contadores no sean del todo exactos.

    Blue.print(IntToStr(Dir_2));
    Blue.print(IntToStr(Pulsos_2));
    Blue.print(IntToStr(Dir_1));
    Blue.print(IntToStr(Pulsos_1));


Lo siguiente es el envío de los valores hacia el dispositivo Android, previa conversión de entero a cadena de tres caracteres, tarea que realiza la función IntToStr declarada al final del código. Esto en realidad no es necesario para el funcionamiento del dispositivo, puede ser eliminado, simplificando así el programa.

    Pulsos_1 = 0;
    Pulsos_2 = 0;
    attachInterrupt(0, ContarPulsos1, CHANGE);
    attachInterrupt(1, ContarPulsos2, CHANGE);

Por último, se reinicializan los contadores y se reactivan las interrupciones, siendo esta la etapa final del tratamiento de las interrupciones.

    if(Dir_1 < 0) Dir_1 = 0; else if(Dir_1 > 255) Dir_1 = 255;
    if(Dir_2 < 0) Dir_2 = 0; else if(Dir_2 > 255) Dir_2 = 255;
    analogWrite(PWM_I, Dir_1);
    analogWrite(PWM_D, Dir_2);
  }

Finalizando el bucle principal, la puesta en forma de las señales y posterior escritura en los correspondientes pines de salida, código ya comentado en entradas anteriores.

  String IntToStr(int d) {
  if(d < 0) d = 0; else if(d > 255) d = 255;
 
  String s = d;
 
  if(d < 10) s = "00" + s;
  else
    if(d < 100) s = "0" + s;
 
  if(s.length() > 3) s = "Err";
  return s;
}


Esta función se encarga de formatear un entero en una cadena de tres caracteres, entre "000" y "255" y si por algún motivo se produce algún desfasaje, se devuelve la cadena "Err".

La función está íntimamente relacionada a la función de lectura de datos en el programa Android, la que debe recibir cuatro cadenas de tres caracteres cada una, si una cadena no tiene esa longitud, se produciría un desplazamiento de los datos presentados en las etiquetas correspondientes, falseando las lecturas.

Finalmente se encuentra la función que se encarga de setear la dirección de los motores, que es ampliamente general y ya se comentó oportunamente.

Ver el hardware desarrollado.

No hay comentarios.:

Publicar un comentario