Sin más preámbulos, vamos a la guía paso a paso para la construcción de nuestro cuadracóptero.
Aunque no es estrictamente necesario, recomiendo altamente leer un poco sobre los fundamentos de vuelo del dron. Para ello el lector puede leer la página de FUNDAMENTOS como un pequeño abrebocas para familiarizarse con los conceptos básicos.
Y evidentemente, previo a comenzar el proceso de construcción, es necesario reunir todos los materiales que vamos a requerir. Por ello, si el estimado lector aún no lo ha hecho, es necesario visitar la página de MATERIALES para conocer los elementos que se necesitarán, entender la importancia y el funcionamiento de cada uno y conocer los modelos recomendados y los sitios donde pueden conseguirlos.
Mira acá el video correspondiente a este paso del tutorial.
Inicialmente debemos preparar el marco que soportará la estructura de nuestro dron. Asumiendo que se haya elegido el marco F330 o F450, este no vendrá ensamblado, por lo que debemos proceder con su montaje utilizando los tornillos y la llave Bristol provistos como parte del kit (aunque a veces la llave no está incluida, por lo que hará falta conseguirla por nuestra cuenta.)
En esta etapa es importante definir la distribución de los componentes en el marco. Recomiendo dejar el nivel inferior exclusivamente para la batería. En el nivel superior la distribución dependerá de la elección del lector sobre si utilizar el "shield" para el Arduino o no. En caso de no usarlo, se requerirá adaptar un tercer nivel para el marco, dejando el segundo nivel para la IMU y el receptor de comunicaciones y el tercer nivel para el Arduino. Con el "shield" esto no será necesario, ya que este cuenta con las conexiones necesarias para cada elemento.
Una vez el marco esté listo, podemos montar los cuatro motores en cada uno de los extremos. Los huecos para los tornillos en el marco y los motores nos indicarán con facilidad dónde deben ser montados. Algunas personas ensamblan primero las hélices a los motores antes de ponerlos en el marco; yo recomiendo primero montar los motores solos para hacer unas pruebas preliminares en vacío cuando la electrónica esté montada, ya que hacerlo con las hélices puestas desde el comienzo puede ser peligroso.
Podemos aprovechar para ir soldando algunos componentes que requeriremos luego. Por ejemplo, el conector de la batería e incluso los variadores en cuanto a sus cables de alimentación. Podemos verificar que las conexiones sean correctas con la ayuda de un multímetro.
Mira acá el video correspondiente a los pasos 2 y 3 del tutorial.
Vamos a dejar por el momento la parte mecánica para entrar de lleno en la electrónica y comenzar a construir el algoritmo que permitirá controlar a nuestra aeronave. Para ello es tiempo de comenzar a trabajar con el cerebro del dron, la tarjeta Arduino, que funcionará como controlador del aparato.
Al adquirir normalmente una tarjeta Arduino, cualquiera que sea su modelo (recordemos que en este proyecto usaremos un Arduino Uno, aunque es posible trabajar concualquier versión, incluso más pequeña como un Nano o más grande como un Mega) usualmente nos entregarán la tarjeta acompañada de un cable USB para su programación desde un PC. Requerimos entonces descargar el programa necesario para esto. Afortunadamente, al ser Arduino una plataforma de hardware libre, cuenta a su vez con software gratuito para trabajar con él. El entorno de desarrollo integrado (IDE) de Arduino es una aplicación multiplataforma que se utiliza para escribir y cargar programas en la placa, disponible directamente desde la página de Arduino (ver enlace). Recomiendo encarecidamente leer y aprovechar los recursos disponibles en esa misma página en cuanto a literatura sobre Arduino y el lenguaje de programación, así como los tutoriales ofrecidos para sumergirse de lleno en esta magnífica plataforma.
Como al hacer cualquier programa, antes de meternos directamente con el código, es necesario plasmar sobre el papel una conceptualización de lo que se va hacer. ¿Cuál es el propósito de nuestro programa? ¿Cuáles son las entradas disponibles y las salidas deseadas? ¿Cuál es el orden más apropiado para seguir en nuestro algortimo para resolver nuestro problema?
Con esto en mente, debemos plasmar un bosquejo inicial estilo diagrama de bloques, con base en los elementos que conformarán nuestro dron. La figura 4.1 nos presenta este diagrama, teniendo como elemento central la tarjeta de control (la placa Arduino) en relación a los demás componentes. Aquellos relacionados con flechas azules representan entradas al controlador; las flechas verdes son salidas.
Como bosquejo inicial, la figura anterior nos sirve para darnos una idea de la relación entre los componentes de la aeronave. SIn embargo, como siguiente paso es necesario refinar un poco más este diagrama incluyendo información clave que nos permita dimensionar adecuadamente nuestra arquitectura de control y por ende nuestro código. Para ello necesitamos dos consideraciones adicionales: tener en cuenta los tipos y cantidades de señales manejados por cada elemento, y pensar también si requerimos algún otro tipo de señales adicionales a las ya mostradas. Veamos cada punto en detalle:
Al proceso anterior lo llamaremos "conceptualización de hardware". En un nivel básico hemos considerado cómo se han de integrar los elementos de nuestro dron con la tarjeta de control en cuanto al tipo y cantidades de señales. Esto con miras a saber cómo será la conexión física entre los elementos y conocer de antemano las consideraciones respectivas en cuanto a cableado y espacio requerido por estos elementos.
Ahora es necesario proceder con la "conceptualización de software", esto es, considerar a nivel funcional cómo va a operar el dron con miras a desarrollar el programa que controlará el aparato. Como buenos diseñadores, apelaremos nuevamente al uso de un diagrama, esta vez será un diagrama de flujo que de manera breve pero concisa ilustre el proceso secuencial que seguirá nuestro programa de control. El diagrama propuesto se presenta en la figura 4.3.
En principio notamos que el diagrama esta dividido en dos fases: una que llamaremos "inicial" y otra "cíclica". Esto se debe a que la programación del Arduino (o en general de cualquier solución basada en microcontrolador) debe contar con estas dos partes en el programa (en Arduino son denominadas "setup" y "loop"). La primera, que solo se ejecuta una vez, sirve para inicializar el programa en cuanto a las entradas/salidas y tipos de comunicación que se usarán, así como para crear y cargar variables globales y en general para ejecutar procesos que solo se requieran una vez al inicio del programa. La otra fase, como su nombre lo indica, es cíclica y se repite de manera "infinita" y es básicamente donde va toda la parte operativa del programa: lectura de variables o entradas, algoritmo donde se procesan dichas señales y generación de algún tipo de salida.
En nuestra fase inicial asignaremos las entradas y salidas que requerimos utilizar durante el resto del programa. Inicializaremos variables globales que contendrán información importante que se requerirá durante toda la ejecución del programa. También inicializaremos los protocolos de comunicación que se requerirán (por ejemplo, el I2C). Finalmente, pondremos a punto la IMU para su funcionamiento con base a la información suministrada por su fabricante.
En cada fase cíclica haremos una lectura de las señales de la IMU (giroscopios y acelerómetros) y procesaremos esta información para convertirla en la velocidad angular y los ángulos de inclinación que realmente necesitamos. También debemos leer las señales recibidas del control remoto para saber hacia dónde debe moverse el dron en función del comando enviado por el usuario. Con toda esta información recopilada, hemos de programar el algoritmo de control de actitud, para mantener estable el dron mientras se desplaza en la dirección requerida. Siempre debemos prever alguna falla (pérdida de comunicación, bajo nivel de la batería, etc.) por lo que debemos tener esto en cuenta también dentro de nuestro código. Finalmente, con todas estas consideraciones se generarán las señales de control (aquellas que se enviarán a los variadores) y finalmente serán efectivamente enviadas, para luego repetir el proceso una y otra vez (de manera REGULAR, es decir, a una tasa de tiempo constante).
Antes de proceder a conectar todos los componentes y tratar de operar el dron es preferible integrar los elementos uno por uno, hacer pruebas con cada uno de ellos e ir escribiendo el programa completo de forma modular, de forma que sea más ordenada y que nos permita identificar fallos en caso de presentarse.
NOTA: Esta sección es recomendada para aquellos que quieran tener un conocimiento más profundo y detallado de la operación del dron y sus partes, y en ella iremos armando el código parte por parte. Sin embargo, el lector que quiera simplemente construir y poner a volar la aeronave sin preocuparse por los detalles de funcionamiento puede saltarse este paso. Más adelante se podrá descargar el código completo para programar el Arduino.
Hemos decidido trabajar con la IMU MPU-6050, la cual lleva tres acelerómetros y tres giroscopios, uno por cada eje (X, Y y Z). Estos dispositivos miden velocidad angular y aceleración en cada uno de esos ejes. Sin embargo, nosotros requerimos obtener los ángulos de orientación en cada momento, por lo la información obtenida de la IMU no puede usarse directamente; se requieren algunos cálculos para obtener los datos que necesitamos. El MPU-6050 opera con 3.3 voltios, aunque algunas versiones llevan un regulador que permite conectarla a 5V. El Arduino provee salidas de ambos niveles de tensión, así que la alimentación de la IMU no será un problema.
Existe infinidad de recursos y tutoriales en internet sobre esta IMU y su conexión con Arduino. Por lo pronto, recomiendo seguir este (ver tutorial), bastante completo y claro, desde los fundamentos de la IMU hasta un código de ejemplo para ver su funcionamiento. Igualmente se da una introduciión al protocolo I2C, necesario para la comunicación entre el Arduino y la IMU.
Una vez leída y asimilada la información sobre la IMU MPU-6050 y seguido el tutorial, podemos, ahora sí, comenzar a escribir el código que usará nuestro Arduino para controlar el dron. El código suministrado a continuación está debidamente comentado, pero sin embargo haremos una descripción general de las líneas que lo componen. Como recursos adicionales se sugiere también revisar la hoja de datos (ver enlace) y la descripción de los registros (ver enlace) del MPU-6050 para comprender algunas partes del código en cuanto a la configuración previa de la IMU y la manera de acceder a sus datos.
Como ya se explicó en el tutorial, inicialmente debe agregarse la librería "Wire", que permite la comunicación del Arduino a través del protocolo I2C. También definimos una constante IMU_ADDRESS, que de acuerdo a las especificaciones suministradas por el fabricante, es la dirección del MPU-6050 a través del protocolo I2C. El '0x' antes del número indica que el valor está escrito en formato hexadecimal. Definimos luego unas cuantas variables globales que usaremos en los cálculos que haremos con las lecturas de la IMU para obtener la información que realmente necesitamos. Algunas variables son para procesar las lecturas directamente desde la IMU, otras son para la operación de filtrado, que como se vio en el tutorial, es necesaria para obtener una buena mezcla entre las lecturas ruidosas de los acelerómetros y las lecturas a largo plazo inestables de los giroscopios.
En el "setup" inicializaremos la comunicación serial para poder ver la salida de nuestros cálculos en pantalla, recordando que en el código final esto no es necesario y deberá ser comentado, junto con todas las líneas "Serial.print" que son solo para referencia en esta parte del proceso. Iniciamos también "Wire" para activar el protocolo I2C y luego invocaremos una función escrita por nosotros (init_IMU, se explica más adelante) donde se inicializa la IMU a través de un procedimiento de escritura en sus registros indicado por el fabricante. Luego invocaremos otra función definida por nosotros (calibrate) que nos permite calibrar la IMU inicialmente. Finalmente, inicializaremos un "timer" en milisegundos, cuya funcionalidad se verá más adelante.
En el "loop" comenzaremos por leer los datos "crudos" de la IMU a través de otra función personalizada (read_IMU). Comenzamos por ajustar los datos del acelerómetro con los "offset" encontrados en la calibración. Posteriormente, obtenemos el dato en 'g' dividiendo por la sensitividad de cada lectura según indicaciones del fabricante. Con la fórmula de la arcotangente explicada en el tutorial, obtenemos los valores en radianes para los ángulos de "roll" y "pitch" y finalmente los convertimos en grados. Hacemos un proceso similar para los datos obtenidos del giroscopio, con unas consideraciones adicionales. Primero, observamos un "dampening" o amortiguamiento, que consiste en combinar la lectura anterior con la nueva lectura para obtener un dato más estable en el tiempo. Luego, como el dato obtenido es velocidad angular y requerimos el ángulo, debemos "integrar" esta información (recordemos que la velocidad es la derivada de la posición, por lo que para obtener posición a partir de velocidad se debe hacer la operación inversa). Para integrar la velocidad, multiplicamos su valor por el tiempo transcurrido desde la última lectura (por ello usamos el "timer") y finalmente este valor se suma al valor actual del ángulo. Vemos que acotamos las lecturas al rango entre -180° y 180°. Finalmente, se guardan las lecturas de velocidad actuales para utilizar en la fase de "dampening" del siguiente ciclo.
Los ángulos obtenidos con el giroscopio también deben ser corregidos en caso de "transferencia" cuando hay un movimiento de "yaw" (ver la explicación en este excelente VIDEO de Joop Brokking). Finalmente, aplicamos un filtro complementario como el que se explica en el tutorial, para obtener la mejor lectura posible con la cual trabajar.
Aparte de "setup" y "loop" que son procedimientos "por defecto", podemos crear funciones o procedimientos propios que pueden invocarse desde cualquier parte del programa. Hemos creado tres, comenzando por init_IMU(), donde se inicializa la IMU MPU-6050 en función de las indicaciones del fabricante. Vemos que hay tres partes importantes, en la primera se activa la IMU enviando un cero al registro PWR_MGMT_1. Luego se configura el rango (y con ello la sensitividad) del giroscopio escribiendo en el registro GYRO_CONFIG. Igual se hace para el acelerómetro con el registro ACCEL_CONFIG. Luego hacemos un chequeo para ver si la comunicación está marchando bien, verificando que uno de los registros donde acabamos de escribir tenga el valor esperado. Si hay algún error el programa quedará en un bucle infinito, por lo que será la indicación para revisar hardware y conexiones. En caso contrario, se hace una última configuración en el registro CONFIG activando un filtro pasa-bajas para obener lecturas aún más estables.
En read_IMU() hacemos una lectura de los datos del MPU-6050 de acuerdo al protocolo I2C, leyendo 14 registros contiguos. Esto porque cada registro es de 8 bits (o un byte) y la lectura de cada acelerómetro y giroscopio (por cada uno de los 3 ejes) ocupa 16 bits, es decir, dos registros. Entonces tenemos 6 bytes para los acelerómetros más 6 para los giroscopios más 2 bytes adicionales para una lectura de temperatura, o sea 14 bytes. Cada lectura la asignamos a su variable global correspondiente.
En calibrate() hacemos cien lecturas de la IMU para obtener un buen promedio de cada lectura. Si el dron está perfectamente nivelado y la IMU fuera perfecta, deberíamos obtener ceros, pero evidentemente este no es el caso. Obtendremos un valor de "offset" que debemos restar siempre dentro del "loop" a las lecturas obtenidas. Adicionalmente, aprovechamos para inicializar el filtro con los ángulos actuales promediados obtenidos de los acelerómetros.
NOTA: Cuando corras este programa, es importante tomar nota de los offset del acelerómetro, ya que debemos utilizar estos valores en el programa final del dron.
//////////////////////////////////////////////////////////////////////////////////////////////////////////////
// IMU - MPU6050
//////////////////////////////////////////////////////////////////////////////////////////////////////////////
// Lectura de datos de la IMU MPU-6050
// Cálculo de ángulos de inclinación
//////////////////////////////////////////////////////////////////////////////////////////////////////////////
// Incluimos algunas librerías adicionales que vamos a utilizar
#include <Wire.h> // Librería para protocolo I2C
// ALGUNAS DEFINICIONES
#define IMU_ADDRESS 0x68 //Direccion I2C de la IMU
// Variables IMU
int acc[3];
int gyro[3];
int temperature;
float rawX, rawY, rawZ;
float X, Y, Z;
float gyroX, gyroY, gyroZ;
float gx_rate, gy_rate, gz_rate;
float last_gx_rate, last_gy_rate, last_gz_rate;
float rollrad, pitchrad;
unsigned long mtime, looptime;
float angleAx, angleAy, angleAz;
float angleGx, angleGy, angleGz;
float aoffsetX, aoffsetY, aoffsetZ;
float goffsetX, goffsetY, goffsetZ;
float angleFx, angleFy;
// Variable solo para visualización, borrar en el algoritmo final
unsigned long showtime;
void setup()
{
// Inicio del puerto serial a 115200 baudios y mensaje de bienvenida
Serial.begin(115200);
Serial.println("Bienvenido, sistema iniciando...");
// Inicio de comunicación I2C
Wire.begin();
// Inicializamos la IMU
init_IMU();
// Un pequeño "delay" e iniciamos la calibración de la IMU
delay(1000);
Serial.println("Calibrando...");
Serial.println("Mantener la IMU quieta y en posición horizontal");
calibrate();
delay(500);
Serial.println("Calibración finalizada.");
mtime = millis(); // Inicializamos la variable mtime con el valor actual en milisegundos (para uso del giroscopio)
showtime = 500; // Iniciamos esta variable en 500 ms
}
void loop()
{
// Leemos la IMU
read_IMU();
// Obtenemos ángulos de roll and pitch de lecturas del acelerómetro
rawX = acc[0] - aoffsetX;
rawY = acc[1] - aoffsetY;
rawZ = acc[2] - (4095 - aoffsetZ); // Debemos considerar la gravedad; en este caso 1g es igual a 4095
// 1/4096 = 0.0002 (4096 es la sensibilidad según datasheet para el rango que escogimos, usamos el inverso para multiplicar en vez de dividir)
X = rawX*0.0002;
Y = rawY*0.0002;
Z = rawZ*0.0002;
rollrad = atan(Y/sqrt(X*X+Z*Z)); // Ángulo en radianes
pitchrad = atan(X/sqrt(Y*Y+Z*Z)); // Ángulo en radianes
// 180/pi = 57.2958 (factor para convertir a grados)
angleAx = rollrad*57.2958; // Ángulo de roll en grados
angleAy = pitchrad*57.2958; // Ángulo de pitch en grados
// Código para giroscopio (roll, pitch, yaw)
looptime = (millis() - mtime);
mtime = millis();
gyroX = gyro[0] - goffsetX;
gyroY = gyro[1] - goffsetY;
gyroZ = gyro[2] - goffsetZ;
// 1/65.5 = 0.0153 (65.5 es la sensibilidad según datasheet para el rango que escogimos, usamos el inverso para multiplicar en vez de dividir)
gx_rate = gyroX*0.0153;
gy_rate = gyroY*0.0153;
gz_rate = gyroZ*0.0153;
float gx1 = gx_rate;
float gy1 = gy_rate;
float gz1 = gz_rate;
// Filtrado inicial de las mediciones de velocidad angular usando una proporción de la medida anterior y la actual
gx_rate = (0.7*last_gx_rate) + (0.3*gx_rate);
gy_rate = (0.7*last_gy_rate) + (0.3*gy_rate);
gz_rate = (0.7*last_gz_rate) + (0.3*gz_rate);
// Integramos para obtener los ángulos
angleGx = angleGx + (gx_rate * looptime)*0.001; // Convertir a segundos (1/1000)
angleGy = angleGy - (gy_rate * looptime)*0.001; // Medición de pitch rate está invertida
angleGz = angleGz - (gz_rate * looptime)*0.001; // Medición de yaw rate está invertida
// Corrección de "yaw" para los ángulos obtenidos del giroscopio
// pi/180 = 0.0174 (para convertir a radianes, luego *0.001 para convertir a segundos
angleGx -= angleGy * sin((gz_rate * looptime)*0.0000174); // Si hubo "yaw" tranferir ángulo de pitch a roll
angleGy += angleGx * sin((gz_rate * looptime)*0.0000174); // Si hubo "yaw" tranferir ángulo de roll a pitch
// Limitamos los ángulos al rango entre -180 y 180 grados
if (angleGx < -180) angleGx += 360;
if (angleGx > 180) angleGx -= 360;
if (angleGy < -180) angleGy += 360;
if (angleGy > 180) angleGy -= 360;
if (angleGz < 0) angleGz += 360;
if (angleGz > 360) angleGz -= 360;
// Guardar valores actuales para el próximo ciclo
last_gx_rate = gx_rate;
last_gy_rate = gy_rate;
last_gz_rate = gz_rate;
// Corrección de "yaw" para los ángulos obtenidos del giroscopio
// pi/180 = 0.0174 (para convertir a radianes, luego *0.001 para convertir a segundos
angleFx -= angleFy * sin((gz_rate * looptime)*0.0000174); // Si hubo "yaw" tranferir ángulo de pitch a roll
angleFy += angleFx * sin((gz_rate * looptime)*0.0000174); // Si hubo "yaw" tranferir ángulo de roll a pitch
// Aplicar el Filtro Complementario a los ángulos originales
angleFx = 0.995*(angleFx + (gx_rate * looptime*0.001)) + 0.005*angleAx;
angleFy = 0.995*(angleFy - (gy_rate * looptime*0.001)) + 0.005*angleAy;
// Limitamos los ángulos al rango entre -180 y 180 grados
if (angleFx < -180) angleFx += 360;
if (angleFx > 180) angleFx -= 360;
if (angleFy < -180) angleFy += 360;
if (angleFy > 180) angleFy -= 360;
// Sección para visualización de las lecturas
if (millis() > showtime){
// Leemos por el puerto serial cada 500 ms
// Valores crudos
Serial.println("Valores crudos");
Serial.print("AcX: "); Serial.print(rawX); Serial.print("\t");
Serial.print(" AcY: "); Serial.print(rawY); Serial.print("\t");
Serial.print(" AcZ: "); Serial.println(rawZ);
Serial.print("GyX: "); Serial.print(gyroX); Serial.print("\t");
Serial.print(" GyY: "); Serial.print(gyroY); Serial.print("\t");
Serial.print(" GyZ: "); Serial.println(gyroZ);
Serial.println("");
// Valores finales
Serial.println("Valores calculados de ángulos");
Serial.print("Roll: "); Serial.print(angleFx); Serial.print("\t");
Serial.print("Pitch: "); Serial.println(angleFy);
Serial.println("Velocidad angular");
Serial.print("Eje x: "); Serial.print(gx_rate); Serial.print("\t");
Serial.print("Eje y: "); Serial.print(gy_rate); Serial.print("\t");
Serial.print("Eje z: "); Serial.println(gz_rate);
Serial.println("");
showtime += 500; // Incrementar variable en 500 ms
}
}
// ------------Funciones complementarias---------------
// Inicializar la IMU
void init_IMU() {
Wire.beginTransmission(IMU_ADDRESS); // Comenzar comunicación con la dirección de la IMU.
Wire.write(0x6B); // Escribir al registro PWR_MGMT_1 (6B hex)
Wire.write(0x00); // Escribir 00000000 para activar la IMU
Wire.endTransmission(); // Finalizar la transmisión
Wire.beginTransmission(IMU_ADDRESS); // Comenzar comunicación con la dirección de la IMU.
Wire.write(0x1B); // Escribir al registro GYRO_CONFIG (1B hex)
Wire.write(0x08); // Escribir 00001000 (Rango 500 °/s)
Wire.endTransmission(); // Finalizar la transmisión
Wire.beginTransmission(IMU_ADDRESS); // Comenzar comunicación con la dirección de la IMU.
Wire.write(0x1C); // Escribir al registro ACCEL_CONFIG (1A hex)
Wire.write(0x10); // Escribir 00010000 (Rango +/- 8g)
Wire.endTransmission(); // Finalizar la transmisión
// Pequeña revisión para verificar los valores enviados
Wire.beginTransmission(IMU_ADDRESS); // Comenzar comunicación con la dirección de la IMU.
Wire.write(0x1B); // Leer registro 0x1B
Wire.endTransmission(); // Finalizar la transmisión
Wire.requestFrom(IMU_ADDRESS, 1); // Solicitar 1 byte
while(Wire.available() < 1); // Esperar la recepción de la información
if(Wire.read() != 0x08){ // Verificar que el valor es 0x08
while(1) delay(10); // Quedarse en este "loop"
}
Wire.beginTransmission(IMU_ADDRESS); // Comenzar comunicación con la dirección de la IMU.
Wire.write(0x1A); // Escribir al registro CONFIG (1A hex)
Wire.write(0x03); // Escribir 00000011 (Low Pass Filter to ~43Hz)
Wire.endTransmission(); // Finalizar la transmisión
}
// Leer la IMU
void read_IMU(){
Wire.beginTransmission(IMU_ADDRESS); // Comenzar comunicación con la dirección de la IMU.
Wire.write(0x3B); // Leer desde registro 3B
Wire.endTransmission(); // Finalizar la transmisión
Wire.requestFrom(IMU_ADDRESS,14); // Solicitar 14 bytes
while(Wire.available() < 14); // Esperar recepción de la información
acc[0] = Wire.read()<<8|Wire.read(); // Concatenar low y high byte de acelerómetro en eje x.
acc[1] = Wire.read()<<8|Wire.read(); // Concatenar low y high byte de acelerómetro en eje y.
acc[2] = Wire.read()<<8|Wire.read(); // Concatenar low y high byte de acelerómetro en eje z.
temperature = Wire.read()<<8|Wire.read(); // Concatenar low y high byte en la variable temperature.
gyro[0] = Wire.read()<<8|Wire.read(); // Concatenar low y high byte de giroscopio en eje x.
gyro[1] = Wire.read()<<8|Wire.read(); // Concatenar low y high byte de giroscopio en eje y.
gyro[2] = Wire.read()<<8|Wire.read(); // Concatenar low y high byte de giroscopio en eje z.
}
// Rutina de calibración
void calibrate() {
// Leemos cien datos de la IMU y obtenemos los respectivos promedios
for (int i = 0; i < 100; i++) {
read_IMU();
if (i == 0) {
aoffsetX = acc[0];
aoffsetY = acc[1];
aoffsetZ = acc[2];
goffsetX = gyro[0];
goffsetY = gyro[1];
goffsetZ = gyro[2];
}
if (i > 0) {
aoffsetX = (acc[0] + aoffsetX);
aoffsetY = (acc[1] + aoffsetY);
aoffsetZ = (acc[2] + aoffsetZ);
goffsetX = (gyro[0] + goffsetX);
goffsetY = (gyro[1] + goffsetY);
goffsetZ = (gyro[2] + goffsetZ);
}
}
aoffsetX = aoffsetX*0.01;
aoffsetY = aoffsetY*0.01;
aoffsetZ = aoffsetZ*0.01;
goffsetX = goffsetX*0.01;
goffsetY = goffsetY*0.01;
goffsetZ = goffsetZ*0.01;
// Los valores obtenidos son el "offset" inicial de los giroscopios y acelerómetros
Serial.print("Los offset del GYRO son: ");
Serial.print(goffsetX);
Serial.print(", ");
Serial.print(goffsetY);
Serial.print(", ");
Serial.println(goffsetZ);
Serial.print("Los offset del ACC son: ");
Serial.print(aoffsetX);
Serial.print(", ");
Serial.print(aoffsetY);
Serial.print(", ");
Serial.println(aoffsetZ);
// Esta parte es para dar un valor inicial a los ángulos calculados con el giroscopio y el filtro, a partir del acelerómetro
// Volvemos a leer la IMU para obtener datos promedio del acelerómetro
float acc_x = 0, acc_y = 0, acc_z = 0;
for (int i = 0; i < 10; i++) {
read_IMU();
acc_x += acc[0];
acc_y += acc[1];
acc_z += acc[2];
}
// Promedio de 10 lecturas
acc_x *= 0.1;
acc_y *= 0.1;
acc_z *= 0.1;
rawX = acc_x - aoffsetX;
rawY = acc_y - aoffsetY;
rawZ = acc_z - (4095 - aoffsetZ); // Debemos considerar la gravedad; en este caso 1g es igual a 4095
// 1/4096 = 0.0002 (4096 es la sensibilidad según datasheet para el rango que escogimos, usamos el inverso para multiplicar en vez de dividir)
X = rawX*0.0002;
Y = rawY*0.0002;
Z = rawZ*0.0002;
rollrad = atan(Y/sqrt(X*X+Z*Z)); // Ángulo en radianes
pitchrad = atan(X/sqrt(Y*Y+Z*Z)); // Ángulo en radianes
// 180/pi = 57.2958 (factor para convertir a grados)
angleAx = rollrad*57.2958; // Ángulo de roll en grados
angleAy = pitchrad*57.2958; // Ángulo de pitch en grados
// Inicializamos los filtros con estos ángulos obtenidos
angleGx = angleAx;
angleGy = angleAy;
angleFx = angleAx;
angleFy = angleAy;
}
Como describimos en la sección de "Materiales" nuestro sistema de comunicaciones contará con dos elementos: el transmisor, desde donde el usuario envía los comandos, y el receptor que va en la aeronave. De manera simple, el transmisor lee los comandos transmitidos con las palancas y botones que el usuario manipula y envía las señales de manera inalámbrica al receptor de forma aparentemente instantánea. El receptor en el dron recibe esta información y la transmite a su vez al módulo de control, el cual procesará estas señales y moverá la aeronave de acuerdo a ellas.
En general se usarán ondas de radio para esta comunicación, en la banda de 2.4 GHz. El sistema contará al menos con cuatro canales diferentes, uno por cada comando de las palancas (potencia, cabeceo o "pitch", alabeo o "roll" y guiñada o "yaw"), pudiendo incluir más canales para funcionalidades adicionales. En el receptor estas señales tendrán, usualmente, los nombres de las superficies de control que manejarían cada tipo de movimiento en un avión. Es decir, el cabeceo en un avión sería controlado por el elevador (elevator), el alabeo por los alerones (ailerons), la guiñada por el timón de dirección (rudder) y la potencia por el suministro de combustible (throttle). Así pues, estos serán los nombres de los pines que encontraremos en el receptor.
Retomando las características del sistema de comunicaciones, podemos mencionar que el rango, o distancia de operación entre transmisor y receptor, suele ir desde unos cientos de metros hasta un kilómetro, variando en función de la potencia del transmisor, la sensibilidad del receptor y la calidad de las antenas en ambos extremos.
El proceso desde que las señales son leídas en el control remoto hasta su interpretación en la tarjeta de control consiste de varias etapas, pero de una forma muy general podemos ver en la figura 5.2.1 cómo la señal de RF generada varía su período (o su frecuencia, recordemos que una es el inverso de la otra) en función de la magnitud del comando enviado por el usuario.
Sin embargo, para propósitos de la programación de nuestro controlador, lo que más nos interesa es lo que sucede en el receptor. La señal es recogida por este elemento, el cual genera a su vez una señal de salida por cada uno de los canales. El estándar de estas señales, tal cual como es implementado en gran parte de los dispositivos en el mercado, consiste en un pulso que varía su período entre 1000 y 2000 microsegundos, como se ve en la figura 5.2.2. En otras palabras, recibimos una señal de modulación de ancho de pulso o PWM. Así pues, nuestra misión es leer apropiadamente cuál es el ancho del pulso que estamos recibiendo por cada canal y traducir ese valor en el movimiento deseado. ¿Cómo haremos tal cosa? A continuación lo explicaremos.
En este proceso debemos tener en cuenta dos conceptos relacionados con Arduino: el uso de contadores o "timers" y las interrupciones. De manera sencilla, un "timer" es un elemento que contabiliza el tiempo transcurrido desde que se energizó el Arduino hasta el momento "actual". Ya hemos hecho uso de uno de ellos en la parte anterior al integrar la IMU; sin embargo, valga decir que puede haber "timers" en milisegundos o en microsegundos. Para esta parte usaremos del segundo tipo, pues nos darán una medida más exacta del pulso que estamos leyendo del receptor.
En Arduino un programa corre de manera secuencial. Sin embargo, si queremos estar atentos a algún evento que suceda independientemente de la secuencia de nuestro programa y reaccionar al mismo, debemos utilizar las interrupciones. Como su nombre lo indica, consisten en una herramienta que permite "interrumpir" temporalmente la ejecución del programa principal para ejecutar algún sub-proceso en respuesta a algún evento. Recomiendo revisar algún tutorial sobre el tema, como este (ver enlace) para una mayor comprensión sobre su uso.
Una vez leída y asimilada la información sobre el funcionamiento del sistema de comunicaciones, pasamos a escribir el código que usará nuestro Arduino para controlar el dron involucrando este sistema. El código suministrado a continuación está debidamente comentado, pero sin embargo haremos una descripción general de las líneas que lo componen.
Comenzamos definiendo unas cuantas variables globales que usaremos para llevar la cuenta del valor en microsegundos del período de cada pulso recibido del receptor por parte del Arduino. Entre estas variables destacamos la que hemos llamado receiver_input[4], que es básicamente un arreglo de 4 campos en cada uno de los cuales guardaremos el valor respectivo del comando de elevación, cabeceo, alabeo y guiñada.
En el "setup" iniciamos configurando unas interrupciones necesarias para leer las señales enviadas por el receptor. Cuando trabajamos con Arduino UNO, podemos usar dos pines para interrupciones externas a través del lenguaje Arduino. Sin embargo, como ya hemos dicho, en este caso se requieren cuatro pines, uno por cada salida del receptor. En ese caso, debemos programar a un nivel más "bajo" para poder acceder a un número mayor de interrupciones externas. Con "nivel más bajo" me refiero a programar directamente los registros del microcontrolador, lo cual también está permitido a través de la interfaz de Arduino. Para ello debemos consultar la hoja de datos del microcontrolador sobre el cual está basado el Arduino UNO, que es el AtMega328P (ver enlace). Al revisar el apartado sobre interrupciones, allí encontraremos qué registros debemos modificar dependiendo de los pines que queramos utilizar. En este proceso usaremos los pines 4, 5, 6 y 7 del Arduino, que corresponden a los campos PCINT20, PCINT21, PCINT22 y PCINT23 del registro PCMSK2 del microcontrolador AtMega328P. A su vez, para activar el registro PCMSK2 debemos activar el campo PCIE2 en el registro PCICR. Todo este proceso que suena aparentemente complicado, en realidad es bastante simple y se resume en las cinco líneas de código que se muestran abajo correspondientes a este párrafo (líneas 21 a 25). Una explicación más detallada puede encontrarse en un tutorial sobre el tema, como este (ver enlace).
En el "loop" comenzaremos por leer los valores recibidos de cada pin conectado al receptor y almacenarlos en variables apropiadas. Pero, ¿de dónde han salido estos valores? En efecto, el arreglo "receiver_input[4]" está siendo modificado en otra parte. Como dijimos anteriormente, esta variable es afectada por la interrupción en cada uno de los pines que hemos configurado para tal efecto. Las interrupciones son manejadas por rutinas especiales, aparte del "setup" y del "loop" que ya conocemos. Esta rutina vendrá más adelante en el código. Por lo pronto, para efectos de esta parte, simplemente mostraremos en el monitor serial de Arduino los valores leídos de cada variable.
La rutina especial para las interrupciones que hemos decidido utilizar se llama ISR(PCINT2_vect). ISR viene de "Interruption Service Rutine", de las cuales existen varias asociadas a diferentes vectores, conforme se explica en los tutoriales ya referidos. En este caso debemos utilizar el vector PCINT2_vect que es el que corresponde a una interrupción por cambio en cualquiera de los pines asociados al registro PCINT2, lo cual es el caso de los cuatro pines que hemos configurado. Ahora bien, esta rutina se ejecuta cuando hay un cambio de valor alto a bajo o viceversa en CUALQUIERA de los pines, razón por la cual lo primordial en esta rutina es establecer cuál pin produjo la interrupción. Veamos el proceso para el canal 1, tras lo cual el procedimiento es similar para todos los demás. Podemos ver que comenzamos leyendo el valor actual de tiempo transcurrido en microsegundos a través de la función micros(). Luego debemos revisar qué canal produjo la interrupción. Para ello primero debemos echar un vistazo de nuevo a la hoja de datos del AtMega328P (o mejor, a un diagrama "pinout" entre Arduino UNO y microcontrolador como este, donde verificamos que los pines 7 a 4 del Arduino corresponden a los pines PD7 a PD4 del micro (la D hace referencia a que estos pines pertenecen al puerto D) y por consiguiente, si se quiere leer el valor actual de entrada en esos pines, debemos consultar los campos 7 a 4 del registro PIND.
Al verificar "if(PIND & B10000000)" estamos haciendo una operación bit a bit, dónde el resultado será 1 (o "true") si y sólo sí el primer campo de PIND, que corresponde a PD7, es ALTO actualmente. Si ese es el caso, como hemos guardado el valor anterior de este pin, verificamos si hubo un cambio de BAJO a ALTO (o de 0 a 1), guardamos el nuevo valor del pin y también el valor actual en microsegundos, o en otras palabras, empezamos a correr una variable "timer". En caso de que el valor del pin sea BAJO, verificamos si se produjo un cambio de ALTO a BAJO (de 1 a 0), recordamos el estado para la próxima interrupción y hacemos una resta entre el tiempo actual y el valor de la variable "timer" que guardamos cuando se produjo al cambio inicial de 0 a 1. En otras palabras, estamos contando en microsegundos el valor de un pulso ALTO como el de la figura 5.2.2 que es la señal que esperamos del receptor. El procedimiento es igual para cada uno de los demás canales.
El resultado obtenido al leer estas señales debería variar siempre entre 1000 y 2000. Además, verificando cuál es la variable que cambia podemos saber cómo están configuradas las palancas de nuestro control, es decir, cuál es la elevación, cuál el cabeceo y así.
//////////////////////////////////////////////////////////////////////////////////////////////////////////////
// Comunicaciones: Transmisor + Receptor
//////////////////////////////////////////////////////////////////////////////////////////////////////////////
// Lectura de los pulsos recibidos del sistema transmisor / receptor
// Decodificación de señales de pulsos a números enteros
//////////////////////////////////////////////////////////////////////////////////////////////////////////////
// Variables control remoto
volatile int rollref, pitchref, yawref, href;
byte last_channel_1, last_channel_2, last_channel_3, last_channel_4;
int receiver_input[4];
unsigned long timer_1, timer_2, timer_3, timer_4, current_time;
void setup()
{
// Inicio del puerto serial a 115200 baudios y mensaje de bienvenida
Serial.begin(115200);
Serial.println("Bienvenido, sistema iniciando...");
// Configuramos las interrupciones para recibir los comandos remotos
PCICR |= (1 << PCIE2); // PCIE2 activado para habilitar PCMSK2 scan.
PCMSK2 |= (1 << PCINT23); // PCINT23 (D7) activado para disparar una interrupción si hay cambio de estado.
PCMSK2 |= (1 << PCINT22); // PCINT22 (D6) activado para disparar una interrupción si hay cambio de estado.
PCMSK2 |= (1 << PCINT21); // PCINT21 (D5) activado para disparar una interrupción si hay cambio de estado.
PCMSK2 |= (1 << PCINT20); // PCINT20 (D4) activado para disparar una interrupción si hay cambio de estado.
Serial.println("Interrupciones configuradas.");
}
void loop()
{
// Leemos las entradas del transmisor remoto
href = receiver_input[0];
rollref = receiver_input[1];
pitchref = receiver_input[2];
yawref = receiver_input[3];
// Vemos las lecturas de las señales recibidas
Serial.println("Señales recibidas: ");
Serial.print("Throttle: "); Serial.print(href); Serial.print("\t");
Serial.print("Roll: "); Serial.print(rollref); Serial.print("\t");
Serial.print("Pitch: "); Serial.print(pitchref); Serial.print("\t");
Serial.print("Yaw: "); Serial.println(yawref);
// Un "delay" para facilitar la lectura, pero que debe eliminarse en operación normal.
delay(500);
}
///////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
// RUTINA DE INTERRUPCIÓN
// Esta rutina es invocada cada vez que alguno de los pines 7, 6, 5 o 4 cambia de estado, para leer las señales del receptor.
///////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
ISR(PCINT2_vect){
current_time = micros();
//Channel 1=========================================
if(PIND & B10000000){ // ¿El pin 7 está ALTO?
if(last_channel_1 == 0){ // Si cambió de 0 a 1...
last_channel_1 = 1; // Guardar estado actual.
timer_1 = current_time; // Guardar tiempo actual en timer_1.
}
}
else if(last_channel_1 == 1){ // Si el pin 7 está en BAJO y pasó de 1 a 0.
last_channel_1 = 0; // Guardar estado actual.
receiver_input[0] = current_time - timer_1; // El valor de este canal es current_time - timer_1.
}
//Channel 2=========================================
if(PIND & B01000000 ){ // ¿El pin 6 está ALTO?
if(last_channel_2 == 0){ // Si cambió de 0 a 1...
last_channel_2 = 1; // Guardar estado actual.
timer_2 = current_time; // Guardar tiempo actual en timer_2.
}
}
else if(last_channel_2 == 1){ // Si el pin 6 está en BAJO y pasó de 1 a 0.
last_channel_2 = 0; // Guardar estado actual.
receiver_input[1] = current_time - timer_2; // El valor de este canal es current_time - timer_2.
}
//Channel 3=========================================
if(PIND & B00100000 ){ // ¿El pin 5 está ALTO?
if(last_channel_3 == 0){ // Si cambió de 0 a 1...
last_channel_3 = 1; // Guardar estado actual.
timer_3 = current_time; // Guardar tiempo actual en timer_3.
}
}
else if(last_channel_3 == 1){ // Si el pin 5 está en BAJO y pasó de 1 a 0.
last_channel_3 = 0; // Guardar estado actual.
receiver_input[2] = current_time - timer_3; // El valor de este canal es current_time - timer_3.
}
//Channel 4=========================================
if(PIND & B00010000 ){ // ¿El pin 4 está ALTO?
if(last_channel_4 == 0){ // Si cambió de 0 a 1...
last_channel_4 = 1; // Guardar estado actual.
timer_4 = current_time; // Guardar tiempo actual en timer_4.
}
}
else if(last_channel_4 == 1){ // Si el pin 4 está en BAJO y pasó de 1 a 0.
last_channel_4 = 0; // Guardar estado actual.
receiver_input[3] = current_time - timer_4; // El valor de este canal es current_time - timer_4.
}
}
Como se ha explicado ya en la sección de "Materiales", los motores y variadores van de la mano y por eso nos referiremos a ellos como una única entidad en esta sección. Acá presentaremos el código para incorporar estos elementos a nuestro "código maestro" del sistema de control, pero también es útil mostrar un programa alternativo que podemos usar para calibrar adecuadamente los motores (y al mismo tiempo verificar el sentido de giro de los motores).
Los variadores o ESCs se componen de dos cables de entrada y tres cables de salida gruesos. Los primeros corresponden a la entrada de alimentación de la batería, mientras los segundos son la señal de salida hacia los motores. Los cables de alimentación deben conectarse entonces, ya sea al marco o a la tarjeta de distribución de potencia. Para la conexión a los motores no es claro cómo hacerla al comienzo, por lo que mi recomendación es simplemente conectar los cables centrales entre sí, y los extremos de cualquier manera. Durante la calibración verificaremos también el sentido de giro que tenga el motor y en caso de no ser correcto, simplemente invertiremos la conexión de los cables de los extremos.
Ahora tenemos el conector con dos o tres cables más delgados, los cuales van conectados a la tarjeta de control. Ya vimos que el tercer cable significa que el ESC lleva incluido BEC. Cuando tenemos estos tres cables, normalmente sus colores son naranja para la señal, rojo para +5 VDC del BEC y café para tierra (ver imagen 5.3.1). Por tanto, respetaremos esa convención para la conexión con el Arduino, del cual usaremos los pines 8, 9, 10 y 11 para las señales de control de los cuatro variadores.
Comenzaremos con la elaboración de un código simple para calibrar y probar los motores. Para comenzar es necesario decir qué tipo de señal esperan recibir los variadores como señal de control. Convenientemente, así como vimos en la sección anterior sobre el módulo de comunicaciones, donde la salida de este es una señal de PWM con un ancho de pulso variable entre 1000 y 2000 microsegundos, igualmente ese es el tipo de señal que cada ESC debe recibir para operar su motor respectivo. Es decir, con un pulso de 1000 microsegundos debemos esperar los motores totalmente quitos, mientras con 2000 microsegundos estos operarán a máxima velocidad.
Para asegurar que los motores/variadores operarán en ese rango, debe realizarse inicialmente un procedimiento de calibración, que en términos simples consiste en enviar a los variadores la señal máxima esperada, seguida de la mínima. El variador responderá a esta secuencia con unos pitidos caracterísiticos que nos indicarán que la calibración fue exitosa. Vamos a construir entonces el código con este objetivo.
Inicialmente agregaremos la librería "Servo", que permite controlar servomotores, como su nombre lo indica. Sin embargo, dado el parecido en el tipo de señales requeridas para esos motores con la que requerimos para nuestros motores sin escobillas, esta librería nos será igualmente útil. Declararemos entonces los cuatro variadores, cada uno como un elemento SERVO, utilizando la librería previamente definida. También declaramos una variable "option" para seleccionar el motor a calibrar o probar.
En el "setup" comenzaremos por asignar cada ESC a un pin del Arduino, utilizando la función "attach()" en la cual tenemos como argumentos el pin a asignar (usaremos 8, 9, 10 y 11 en este tutorial), el valor mínimo y el valor máximo a usar en microsegundos (1000 y 2000, respectivamente, como ya se explicó). Luego debemos "armar" los motores escribiendo un cero a cada uno. Este paso no es estrictamente necesario para la calibración si solo tenemos un motor conectado a la vez. Sin embargo, en este caso asumimos que los cuatro están conectados (aunque solo vamos a calibrar uno a la vez) por lo cual este paso evita algún arranque accidental de los motores que no están siendo utilizados en este momento. A continuación escribimos el valor MÁXIMO (2000) al motor que vamos a calibrar. Recomiendo hacerlo con un solo motor a la vez, para poder escuchar claramente la serie de pitidos que emite el motor durante el proceso y no mezclarlos con los demás. Finalmente iniciamos el puerto serial para interactuar con el Arduino a través de la consola, invocamos una función "menu()" definida por nosotros (se explica más adelante) y enviamos un mensaje para introducir un valor entre 1000 y 2000.
En el "loop" simplemente leemos lo que se esté enviando por el puerto serial. Se recomienda al lector seguir tutoriales sencillos para familiarizarse con la lectura y escritura del puerto serial a través de Arduino en caso de requerirlo. Básicamente en este proceso estamos leyendo una cadena de caracteres enviado por el usuario, donde se espera que este introduzca un número entre 1000 y 2000 seguido de la tecla "enter". Si los datos introducidos no corresponden a este patrón, se enviará un mensaje solicitando los datos correctos. Si el número introducido es correcto, simplemente se escribe ese valor al motor escogido.
Nuetra función menu() simplemente envía un mensaje pidiendo seleccionar el motor a probar o calibrar, lo cual corresponde a un número del 1 al 4 y carga este valor en la variable "option". Si el valor digitado no es correcto, simplemente solicita repetir el procedimiento hasta que el número ingresado sea válido. Esta función hace uso a su vez de una función read_serial() que es básicamente otra función para leer lo que se envía por el puerto serial y en el caso particular de que sea un número entero válido, convertirlo a tipo numérico para poder trabajar con él.
//////////////////////////////////////////////////////////////////////////////////////////////////////////////
// Motores / ESC (Variadores)
//////////////////////////////////////////////////////////////////////////////////////////////////////////////
// Lectura de los pulsos recibidos del sistema transmisor / receptor
// Decodificación de señales de pulsos a números enteros
//////////////////////////////////////////////////////////////////////////////////////////////////////////////
// Librería para el manejo de los motores
#include
// Declaración de los cuatro motores
Servo esc1;
Servo esc2;
Servo esc3;
Servo esc4;
char dato;
int pulso = 0;
int option;
void setup()
{
// Asignamos cada motor al pin correspondiente y los valores mínimo y máximo de pulso en microsegundos
esc1.attach(8, 1000, 2000);
esc2.attach(9, 1000, 2000);
esc3.attach(10, 1000, 2000);
esc4.attach(11, 1000, 2000);
esc1.write(0); // ¡IMPORTANTE! Para armar el motor correspondiente
esc2.write(0);
esc3.write(0);
esc4.write(0);
// Usar la siguiente línea solo para calibrar; comentar en otro caso
esc1.writeMicroseconds(2000); // Escribimos el valor máximo para calibrar el motor
Serial.begin(115200);
menu();
Serial.print("Introduzca valor de PWM (1000-2000): ");
}
void loop()
{
// Interacción con el usuario para escribir un pulso válido al variador
if (Serial.available()) {
static char input[16];
static uint8_t i;
dato = Serial.read();
if ( dato != '\r' && i < 15 ) // Asumiendo que "Carriage Return" es el caracter utilizado en el monitor serial para el cambio de línea
input[i++] = dato;
else
{
input[i] = '\0';
i = 0;
pulso = atoi(input);
Serial.println(pulso);
if (pulso < 1000 || pulso > 2000){
Serial.println("Numero no valido. Intente de nuevo (1000-2000).");
Serial.print("Introduzca valor de PWM (1000-2000): ");
}else{
switch(option){
case 1:
esc1.writeMicroseconds(pulso);
break;
case 2:
esc2.writeMicroseconds(pulso);
break;
case 3:
esc3.writeMicroseconds(pulso);
break;
case 4:
esc4.writeMicroseconds(pulso);
break;
default:
Serial.println("");
menu();
break;
}
Serial.print("Introduzca valor de PWM (1000-2000): ");
}
}
}
}
//--------- FUNCIONES ADICIONALES ----------------
void menu(){
// Sencilla función para escribir un menú al usuario
Serial.println("Seleccione numero de 1 a 4 para probar motor correspondiente: ");
option = 0;
while (option!=1 && option!=2 && option!=3 && option!=4) option = read_serial();
Serial.print("Ha escogido ");
Serial.println(option);
Serial.println("");
}
int read_serial(){
// Función para leer el puerto serial y convertir texto a número
static char input[16];
static uint8_t i;
int result;
while (Serial.available()) {
dato = Serial.read();
if ( dato != '\r' && i < 15 ) // Asumiendo que "Carriage Return" es el caracter utilizado en el monitor serial para el cambio de línea
input[i++] = dato;
else {
input[i] = '\0';
result = atoi(input);
}
}
return result;
}
El sencillo programa que hemos elaborado nos permite tanto calibrar en primera instancia cada conjunto motor-variador como probar la velocidad de rotación (y el sentido). Para el procedimiento de calibración hay que seguir un secuencia específica.
Este proceso debe hacerse para los cuatro variadores, simplemente variando la línea en el programa donde se escribe la señal máxima (2000 us), asignándola al variador correspondiente. Una vez se haya hecho esto para los cuatro, recomiendo dejar esa línea comentada y volver a cargar el programa, que ahora quedará simplemente de prueba.
Mira acá el video correspondiente a los pasos 4 y 5 del tutorial.