Encoder y Arduino. Tutorial sobre el módulo sensor de velocidad IR con el comparador LM393 (Encoder FC-03) Deja un comentario

En este tutorial muestro como usar el encoder FC-03 o encoder FZ0888 (Módulo sensor de velocidad de infrarrojos con el comparador LM393) o optointerruptor. Lo he implementado en las 4 ruedas del robot Andromina OFF ROAD para calcular la velocidad de giro de estas. Se ha elegido este encoder por que es el más económico que hay en el mercado. Este tutorial muestra las dos mejores soluciones para conectar el encoder FC-03 a Arduino UNO o MEGA sin tener problemas. El encoder se muestra a continuación:

Módulo sensor de velocidad de infrarrojos con el comparador LM393 o encoder FC-03
Encoder FC-03
Imagen de la rueda del robot, del encoder LM393, del disco dentado y del motor
Foto del montaje del motor del robot, del encoder y del disco dentado.

1-El encoder : Con este módulo sensor de velocidad IR con el comparador LM393 podemos calcular la velocidad de rotación de las ruedas de nuestro robot. Si colocamos una corona dentada que gira unida a nuestra rueda. También se podría usar como un interruptor óptico.
El funcionamiento básico de este sensor es el siguiente; Si se hace pasar cualquier cosa entre la ranura del sensor, este crea un pulso digital en el pin D0. Este pulso va de 0V a 5V y es una señal digital TTL. Luego con Arduino podemos leer este pulso.
A continuación describimos las diferentes partes del encoder:

Partes que conforman el encoder FC-03
Principales partes del encoder

Pines de conexión del módulo de velocidad (encoder FC-03):

VCC: Alimentación del módulo de 3,3V a 12V.

GND: Tierra.

D0: Señal digital de los pulsos de salida.

A0: Señal analógica de los pulsos de salida. Señal de salida en tiempo real. (normalmente no se usa).

Principales características técnicas:
Dimensiones: 32 x 14 x 7mm
La ranura de lectura del sensor tiene un ancho de 5mm.
Dos salidas, una Digital y otra Analógica.
LED indicador de alimentación.
LED indicador de los pulsos de salida del pin D0.
2-Pulsos malos: Con este encoder he tenido también problemas a la hora de leer los pulsos digitales que genera el comparador LM-393. Arduino UNO o MEGA lee más pulsos de los que se generan realmente. Lee del orden de 4 veces más pulsos de los que se generan realmente. He buscado información sobre este problema en internet y he encontrado poca. Por lo que he podido aprender, es que este sensor es muy sensible a las interferencias que se puede introducir en los pines VCC y GND. Si alimentamos el sensor desde el propio Arduino a 3,3V o 5V, El regulador de tensión del propio Arduino pueden introducir corrientes parásitas en el sensor. Produciendo que este no funcione correctamente.
Usando un osciloscopio conectado entre los pin D0 y GND y analizado los pulsos que se generan en el encoder. Ver las fotos siguientes:

Señales cuadradas de salida del encoder.
Señal del pulso digital del pin A0.
Señal analógicas de salida del encoder.
Señal del pulso analógico del pin D0.

Si miramos el pulso generado parece que es un pulso cuadrado correcto, pero si se amplia mucho el inicio del pulso se puede ver que el pulso no es cuadrado. Tal y como puede verse en la foto siguiente, la señal digital cuadrada TTL que genera el encoder FC-03 tiene rebotes al inicio del pulso.

Rampa de subida de la señal con muchos rebotes
Rebote inicial de la señal visto con un osciloscopio.

También tiene rebotes al final del pulso. Arduino es muy sensible y lee estos rebotes como pulsos buenos y realmente no lo son. Ver foto siguiente con los rebotes al final del pulso:

Rampa de bajada de la señal con muchos rebotes
Rebote final de la señal visto con un osciloscopio.

3-Dos soluciones : Para solventar este problema, he diseñado dos soluciones. La primera solución es hacer un programa, un “sketch” de Arduino que no lea los rebotes y no lea falsas señales. La segunda solución es colocar un condensador para que elimine los rebotes iniciales y finales.
La solución mejor que propongo para solventar este problema es la siguiente.

4-Solución 1 ; En la figura siguiente se muestra el esquema básico que he realizado en esta solución. El truco consiste en colocar un condensador  de polièster metalizado (o cerámico) entre el pin D0 y el pin GND. Yo he probado con varios condensador diferente. El que me ha dado mejor resultado es el condensador (562J 250v). Este condensador casi no deforma el pulso digital generado por el comparador LM393.
Esta solución es la que mejor que se puede adoptar. Ya que la he ensayado con diferentes placas de Arduino y nunca ha fallado. Yo he probado con Arduino UNO, MEGA y DUE.

Esquema del encoder con el condesador y Arduino
Esquema de conexión del encoder con un condensador.

También he probado con un condensador de 100nF (104), el cual también me ha dado buen resultado. Este condensador deforma más la señal del pulso digital, al ser de mayor capacidad, pero funciona correctamente. En las dos fotos siguientes muestro el condensador soldado a los dos pines del módulo de velocidad. En esta posición el condensador queda perfectamente integrado y no molesta para nada.

El módulo medidor de velocidad y el condensador
Vista del condensador soldado a los dos pines
Encoder LM393
Vista frontal de módulo y el condensador soldado

En la fotografía siguiente se aprecia la rampa de subida de un pulso del encoder con el condensador ya soldado. Podemos ver que los rebotes han desaparecido por completo.

Rampa de subida de la señal sin rebotes
Inicio del pulso con los rebotes eliminados

En la fotografía siguiente se aprecia la rampa de bajada de un pulso del encoder con el condensador ya soldado. Podemos ver que los rebotes han desaparecido, pero aún se aprecia unos pequeños escalones en la señal. Estas pequeñas oscilaciones no son captadas por el Arduino. El cual reconoce el pulso correctamente.

Rampa de bajadas de la señal sin rebotes
Final del pulso con los rebotes eliminados

Esta solución es muy buena, ya que no se envían al Arduino falsas señales y el programa no tiene que perder el tiempo verificando si la señal es buena o mala. De esta manera solo se activa la interrupción del Arduino cuando la señal es correcta.

5-Diseño : Este encoder se a implementado en el robot Andromina OFF ROAD. Para medir la velocidad del robot, podemos poner solo dos encoders en dos ruedas o poner 4 encoders en las 4 ruedas.

Robot 4x4 Andromina OFF ROAD
Vista del chasis del robot Andromina OFF ROAD.

A continuación se enseña el esquema básico de la conexión de los 4 encoders FC-03 al Arduino MEGA para un robot 4×4. Este esquema no se puede implementar en el Arduino UNO ya que solo tiene 2 pines con interrupciones. El Arduino MEGA tiene 6 pines con interrupciones, que son ; 2, 3, 18, 19, 20 y 21.

Esquema Arduino con 4 encoders
Esquema del robot con los conexión de los 4 encoders.

En la foto siguiente se puede apreciar todas las piezas que conforman el conjunto motriz; la rueda, el disco dentado, el encoder, el motor del robot y el soporte del motor. He diseñado un disco dentado que se acopla a la llanta de la rueda. Este disco lo he diseñado con 20 dientes. Con este número de dientes el encoder tiene una óptima presición. También he diseñado un nuevo soporte de motor para poder atornillar el encoder al motor.

Las diferentes partes que conforman el conjunto encoder/motor
Vista de todas las piezas que conforman el motor del robot.

En la foto siguiente se muestra como queda el ensamblaje entre el motor, el encoder y la rueda. Queda un conjunto muy compacto y robusto.

Vista del micro motor y del sensor de velocidad
Vista de como queda el encoder montado en el motor.

6-Truco : El truco siguiente solo me ha funcionado con una placa Arduino UNO original. Lo he probado con una placa Arduino Mega no original y no funcionaba.

Para que el encoder FC-03 funcione correctamente con Arduino UNO Original. Se tiene que alimentar el pin VCC del encoder con un voltaje de 3,3v, desde el pin de 3,3V del Arduino. De esta manera el encoder da una señal de pulsos sin interferencias. No se necesita colocar ningún condensador. Ver el esquema de conexión siguiente:

Esquema del encoder y Arduino alimentado a 3,3V.
Esquema de conexión del encoder alimentado a 3,3V.

Si el pin VCC del encoder FC-03 se alimenta con una tensión de 5 Voltios se generan corrientes parásitas (rebotes) en la señal digital de pulsos y Arduino no lee bien los pulsos del encoder. Leyendo más pulsos de los que realmente se generan.
A continuación se muestran las diferentes señales que salen de los dos pines del módulo.

Pulso analógico que nos da el pin A0.
Señal analógica de los pulsos de la salida del pin A0.
Pulso digital que nos da el pin D0.
Señal digital de los pulsos de la salida del pin D0.

En la gráfica siguiente se puede ver como el pulso cuadrado digital se ha deformado un poco en su inicio debido a la colocación de un condensador.

Pulso digital deformado que nos da con el condensador
Señal digital de los pulsos de la salida del pin D0 con un condensador (104)

7-Solución 2; Aquí presento la solución  mediante “software”. En el siguiente “sketch” de Arduino se soluciona el problema de los rebotes en los pulsos digitales del encoder. Con la función “counter” del “sketch”. Esta función se activa por medio de una interrupción en el pin 2 de Arduino, cuando se detecta la rampa de subida del pulso. Para no contar los rebotes la función primero lee la rampa de subida, luego comprueba que ha pasado unos 500 micro-segundos desde la última lectura de un pulso y luego vuelve a leer la señal del pin 2 para verificar que aún se esta leyendo el pulso entrante. Si todo esto se cumple se cuenta el pulso como bueno. De esta manera evitamos leer los rebotes que se generan al inicio del pulso y al final.
Esta solució es correcta si no queremos poner un condensador. Pero estamos enviado a Arduino señales buenas y señales malas. lo que provoca más interrupciones de las realmente necessaris.

/// Variables //////////////////////////////////////////////////////////////////////////////////////////////////////////////

int encoder_pin = 2;             //Pin 2, donde se conecta el encoder

unsigned int rpm = 0;           // Revoluciones por minuto calculadas.

float velocity = 0;                 //Velocidad en [Km/h]

volatile byte pulses = 0;       // Número de pulsos leidos por el Arduino en un segundo

unsigned long timeold = 0;  // Tiempo

unsigned int pulsesperturn = 20; // Número de muescas que tiene el disco del encoder.

const int wheel_diameter = 64;   // Diámetro de la rueda pequeña[mm]

static volatile unsigned long debounce = 0; // Tiempo del rebote.

////  Configuración del Arduino /////////////////////////////////////////////////////////

void setup(){

Serial.begin(9600); // Configuración del puerto serie

pinMode(encoder_pin, INPUT); // Configuración del pin nº2

attachInterrupt(0, counter, RISING); // Configuración de la interrupción 0, donde esta conectado.

pulses = 0;

rpm = 0;

timeold = 0;

Serial.print(“Seconds “);

Serial.print(“RPM “);

Serial.print(“Pulses “);

Serial.println(“Velocity[Km/h]”);}

////  Programa principal ///////////////////////////////////////////////////////////////////////

void loop(){

if (millis() – timeold >= 1000){  // Se actualiza cada segundo

noInterrupts(); //Don’t process interrupts during calculations // Desconectamos la interrupción para que no actué en esta parte del programa.

rpm = (60 * 1000 / pulsesperturn )/ (millis() – timeold)* pulses; // Calculamos las revoluciones por minuto

velocity = rpm * 3.1416 * wheel_diameter * 60 / 1000000; // Cálculo de la velocidad en [Km/h]

timeold = millis(); // Almacenamos el tiempo actual.

Serial.print(millis()/1000); Serial.print(”       “);// Se envia al puerto serie el valor de tiempo, de las rpm y los pulsos.

Serial.print(rpm,DEC); Serial.print(”   “);

Serial.print(pulses,DEC); Serial.print(”     “);

Serial.println(velocity,2);

pulses = 0;  // Inicializamos los pulsos.

interrupts(); // Restart the interrupt processing // Reiniciamos la interrupción

}

}

////Fin de programa principal //////////////////////////////////////////////////////////////////////////////////

///////////////////////////Función que cuenta los pulsos buenos ///////////////////////////////////////////

void counter(){

if(  digitalRead (encoder_pin) && (micros()-debounce > 500) && digitalRead (encoder_pin) ) {

// Vuelve a comprobar que el encoder envia una señal buena y luego comprueba que el tiempo es superior a 1000 microsegundos y vuelve a comprobar que la señal es correcta.

debounce = micros(); // Almacena el tiempo para comprobar que no contamos el rebote que hay en la señal.

pulses++;}  // Suma el pulso bueno que entra.

else ; }

 

Deja una respuesta

Tu dirección de correo electrónico no será publicada. Los campos obligatorios están marcados con *

Este sitio usa Akismet para reducir el spam. Aprende cómo se procesan los datos de tus comentarios.

Enviar Whatsapp
Hola 👋
¿En qué podemos ayudarte?