Motores, ESC y su programación en Arduino


Índice:

  1.  Conceptos generales sobre drones
  2. Material necesario y montaje de los componentes hardware
  3. Mando RC y receptor. Programación en Arduino
  4. MPU6050 y su programación en Arduino
  5. Batería LiPo
  6. Control de estabilidad y PID
  7. → Motores, ESC y su programación en Arduino
  8. Calibración de hélices y motores
  9. Software completo y esquema detallado
  10. Probando el software completo antes de volar
  11. Como leer variables de Arduino en Matlab

Motores brushless y ESC para drones

Los motores brushless o motores sin escobillas son motores trifásicos de corriente alterna (AC) y son los motores mas utilizados para volar drones.

Comprar motor y ESC en Amazon

El motor girará a una velocidad proporcional a la tensión aplicada en la entrada trifásica. Si tenemos motores 1000KV, estos giraran a 1000rpm (revoluciones por minuto) por cada voltio de alimentación aplicado. Con una batería 3S de 11.1V el motor podría llegar a girar a 11000rpm. ¿Cómo conseguimos convertir los 11.1V (DC) de nuestra batería en tensión alterna (AC) trifásica controlable? Como ya habréis imaginado, utilizando Electronic Speed Controllers (ESCs). Se trata de unos dispositivos que convierten la tensión DC de entrada (batería) en tensión AC regulable a la salida en función de la señal PWM de control que apliquemos.

La señal PWM para gobernar los motores deberá ser de frecuencia constante y de ancho de pulso variable en función de la velocidad de giro que queramos obtener. En la mayoría de ESC, aplicando un pulso de 1000μs el motor permanece parado, con un pulso de 1500μs el motor gira a mitad de velocidad y ante un pulso de 2000μs gira a máxima velocidad. La frecuencia que utilizaremos para gobernar los motores será de 166Hz o 6000μs, mas adelante veremos el por qué. Os dejo unas imágenes obtenidas con osciloscopio de una de las salidas PWM, donde se puede ver como la frecuencia se mantiene constante, y es el ancho de pulso el que varía:

¿Cómo generamos esta salidas PWM? Arduino ya cuenta con una función para generar pulsos, la función WriteMicroseconds() que viene con la librería servo.h. Simplemente hay que indicar entre paréntesis el tiempo de pulso en microsegundos que queremos en la señal PWM. La desventaja de esta función es que genera pulsos a una frecuencia de 50Hz (20ms), lo que resulta demasiado lento para controlar el drone, por lo que no sirve para esta aplicación. Como ya veremos más adelante en una entrada dedicada a los controladores PID y la estrategia de control, para mantener el drone estable en el aire hay que ejecutar los PID cada 5ms (200Hz) o 12ms (85Hz) aproximadamente. Por tanto, no serviría de nada ejecutar el control cada 6ms para enviar la información a los motores cada 20ms. Necesitamos generar los pulsos PWM a la misma frecuencia que ejecutamos el control de estabilidad, de otra manera los ESC recibirán la información suficiente para mantener el drone en el aire. 

Montaje y conexionado entre motor y ESC

El conexionado entre batería-ESC-motor es muy sencillo, basta con cablear la salida trifásica de cada ESC a un motor (el orden de la conexión trifásica es indiferente) y los dos cables de control a la placa Arduino como se muestra en la siguiente figura (el cable rojo central lo dejaremos sin conectar):

La conexión entre ESC y motor debe ser una conexión robusta y sin malos contactos para no dañar los componentes, para lo que recomiendo utilizar conectores adecuados (no estañar los cables). Fue un quebradero de cabeza para mi ver cómo tanto los motores como los ESC dejaban de funcionar sin razón aparente, hasta que tras leer mucho foros especializados llegue a la conclusión que mis conexiones (estañaduras) no eras las más adecuadas. Tras haber cambiado a los siguiente conectores tipo bala no he vuelto a tener problemas. Son muy fáciles de conseguir, simplemente buscadlos como ‘conectores tipo bala’ o ‘conectores tipo bala doble’ (tened en cuenta que hace falta una herramienta especial para apretar estos terminales):

Conector tipo bala. Arduino drone.

Comprar conectores tipo bala en Amazon 

Conexión motor con ESC. Arduino drone.

En cuanto a las señales de control, he utilizado ‘terminales atornillados’ para enviar las señales PWM desde la placa Arduino a cada ESC. Son conectores robustos y que permiten soltar los cables fácilmente en caso de que querer desmontar el drone. Utilizar terminales adecuados también en los cables:Conector atornillado. Arduino drone.

Comprar conectores a tornillos en Amazon

Conexionado drone arduino

Como hemos visto en la entrada dedicada al sensor MPU6050, orientaremos el sensor de forma que la ‘flecha Y‘ quede alineada con lo que consideremos parte ‘delantera’ de nuestro drone. De esta forma, la numeración de los motores tiene que ser la siguiente, siendo el motor delantero derecho siempre el motor número 1. Es imprescindible numerar los motores de esta forma si queréis utilizar el software completo que os he dejado en la entrada número 9:

Numeración de los motores. Drone Arduino

El hecho de numerar los motores va mas allá de simplemente colocarles una etiqueta, hay que conectar cada señal PWM para cada ESC a un pin determinado de la placa Arduino:

  • Motor 1 de la figura superior  ⇒ al pin 3 de la placa Arduino
  • Motor 2 de la figura superior  ⇒ al pin 4 de la placa Arduino
  • Motor 3 de la figura superior  ⇒ al pin 5 de la placa Arduino
  • Motor 4 de la figura superior  ⇒ al pin 6 de la placa Arduino

Otro de los aspectos importantes a la hora de construir nuestro drone es la dirección de giro de los motores. Es muy importante que los motores en diagonal giren en el mismo sentido. La siguiente figura muestra el sentido de giro de cada motor. Ajustaremos el sentido de giro de cada motor hasta que encaje con la figura una vez que hayamos puesto todo en marcha y seamos capaces de hacer girar de los motores de forma controlada:

Sentido de giro de los motores. Drone Arduino.

Para variar el sentido de giro basta con intercambiar dos de loas fases de alimentación del motor:

Código Arduino para control de motores Brushless con ESC

Todo el software que utilizaremos a lo largo de esta entrada está subido a GitHub:

Descargar ficheros en GitHub

Para generar las salidas PWM de control vamos a utilizar el código que os he dejado en GitHub. Simplemente leeremos el canal Throttle del mando radio control y haremos girar los motores moviendo el correspondiente stick del mando (importante haber leído la entrada dedicada a la lectura del mando radio control ). Al principio puede que resulte un tanto complicado de entender, pero en cuento lo tengáis, comprenderéis que es una solución muy simple.

Analicemos el código parte por parte. Lo primero que hacemos al comienzo de cada nuevo ciclo de 6000μs es leer el canal de Throttle del mando y escalar las lecturas para obtener 2000μs con el stick al máximo y 1000μs con el stick al mínimo como hemos visto en la entrada dedicada al mando radio control. Para ello utilizaremos la función map() de Arduino:

//  Nuevo ciclo
while (micros() - loop_timer < usCiclo);
loop_timer = micros();

//  Ecuaciones de procesamiento de la señal Throttle
RC_Throttle_consigna  = map(RC_Throttle_raw, us_min_Throttle_raw, us_max_Throttle_raw, us_min_Throttle_adj, us_max_Throttle_adj);

En este caso, queremos que el ancho de pulso de las señales PWM sea fijado únicamente por la consigna Throttle del mando radio control, es decir, mover lo motores de forma proporcional al canal Throttle:

// La señal RC_Throttle_consigna define el tiempo que la señal PWM está en estado HIGH
ESC1_us = RC_Throttle_consigna;
ESC2_us = RC_Throttle_consigna;
ESC3_us = RC_Throttle_consigna;
ESC4_us = RC_Throttle_consigna;

El siguiente paso es poner las 4 salidas PWM de los 4 motores en estado HIGH y registrar ese instante en la variable  tiempo_motores_start:

// Para generar las 4 señales PWM, el primer paso es poner estas señales a 1 (HIGH).
digitalWrite(pin_motor1, HIGH);  // MOTOR 1
digitalWrite(pin_motor2, HIGH);  // MOTOR 2
digitalWrite(pin_motor3, HIGH);  // MOTOR 3
digitalWrite(pin_motor4, HIGH);  // MOTOR 4
tiempo_motores_start = micros();

Una vez que las cuatro señales PWM están en estado HIGH, sabemos que tenemos un margen de tiempo de 1ms (que es el ancho de pulso mínimo para las señales PWM) donde Arduino no va a hacer nada, solo esperar. Mas adelante veremos como aprovechar ese milisegundo para realizar tareas cortas como leer el mando radio control o gestionar los LEDs. 

Finalmente, sumamos los tiempos ESC1_us, ESC2_us, ESC3_us y ESC4_us, que oscilarán entre 1000us y 2000us, con el instante en el que hemos puesto las señales en estado HIGH (tiempo_motores_start). De esta forma, obtenemos el instante en que hay que bajar las señales PWM a estado LOW para terminar el ciclo PWM

Utilizando el siguiente bucle while, pasamos a estado LOW  las cuatro señales PWM, cada una cuando corresponda. De esta forma conseguimos señales PWM de la misma frecuencia del ciclo que hayamos escogido:

  // Cuando se cumpa el tiempo de PWM definido en ESCx_us, se pasa cada señal a 0 (LOW) para terminar el ciclo PWM.
  while (digitalRead(pin_motor1) == HIGH || digitalRead(pin_motor2) == HIGH || digitalRead(pin_motor3) == HIGH || digitalRead(pin_motor4) == HIGH) {
    if (tiempo_motores_start + ESC1_us <= micros()) digitalWrite(pin_motor1, LOW); // MOTOR 1
    if (tiempo_motores_start + ESC2_us <= micros()) digitalWrite(pin_motor2, LOW); // MOTOR 2
    if (tiempo_motores_start + ESC3_us <= micros()) digitalWrite(pin_motor3, LOW); // MOTOR 3
    if (tiempo_motores_start + ESC4_us <= micros()) digitalWrite(pin_motor4, LOW); // MOTOR 4
  }

Una vez entendido como generar las señales PWM, vamos a proceder a conectar y hacer girar los motores por primera vez. Cuando conectamos los motores por primera vez hay que seguir un procedimiento para configurar los ESC. El esquema mínimo necesario se muestra a continuación, aunque también podemos montar el esquema completo mostrado en la entrada software completo y esquema detallado:

Montaje necesario para mover los motores brushless. Drone Arduino.

 MUY IMPORTANTE: hasta que no tengamos claro el funcionamiento del software y hayamos comprobado que funciona todo bien, NO PONEMOS LAS HÉLICES. Las pondremos mas adelante. Estas pruebas las haremos SIN HÉLICES ⊗

Es necesario configurar los ESC cuando vayamos a utilizarlos por primera vez, para lo que utilizaremos el código de abajo. Si no disponemos de un interruptor se puede hacer la conexión entre la batería y los ESC manualmente, aunque para el montaje final si que es recomendable disponer de uno. Os dejo también un vídeo para para que sigáis los pasos de forma mas sencilla:

  1. Sin conectar la batería, alimentamos la placa Arduino con USB y cargamos este programa.
  2. Ejecutamos el programa sin conectar la batería.
  3. Cuando el led 13 se encienda, encendemos el mando y subimos el throttle al máximo.
  4. Cuando el led 13 se apague conectamos la batería.
  5. El motor emitirá unos pitidos (pi,pi), bajamos el throttle al mínimo.
  6. Escucharemos otros pitidos, pipipi… piiii.
  7. Terminado, ya podemos apagar todo.

** Este proceso puede ser diferente en función del ESC que hayamos comprado

#define usCiclo 6000    // Ciclo de ejecucion de software en microsegundos (PWM)
#define pin_motor1 3    // Pin motor 1
#define pin_motor2 4    // Pin motor 2
#define pin_motor3 5    // Pin motor 3
#define pin_motor4 6    // Pin motor 4
#define pin_Throttle 8  // Pin throttle del mando RC
#define pin_LED_rojo 13 // Pin LED rojo

#include <EnableInterrupt.h>

// PWM
float ESC1_us, ESC2_us, ESC3_us, ESC4_us, loop_timer;
long tiempo_motores_start;

// AJUSTE MANDO RC - THROTLLE
float RC_Throttle_consigna;
const int us_max_Throttle_adj = 2000;
const int us_min_Throttle_adj = 950;
const float us_max_Throttle_raw = 2004; // <-- Si teneis la entrada Throttle invertida sustituid este valor
const float us_min_Throttle_raw = 1116; // <-- por este y viceversa

// INTERRUPCIÓN MANDO RC --> THROTTLE
volatile long Throttle_HIGH_us;
volatile int RC_Throttle_raw;
void INT_Throttle() {
  if (digitalRead(pin_Throttle) == HIGH) Throttle_HIGH_us = micros();
  if (digitalRead(pin_Throttle) == LOW)  RC_Throttle_raw  = micros() - Throttle_HIGH_us;
}

void setup() {

  // Decalaración de LEDs
  pinMode(pin_LED_rojo, OUTPUT);
  digitalWrite(pin_LED_rojo, HIGH);

  // Serial.begin()
  Serial.begin(115200);

  // Interrupción para canal Thrtottle
  pinMode(pin_Throttle, INPUT_PULLUP);
  enableInterrupt(pin_Throttle, INT_Throttle, CHANGE);

  // Decalaración de motores
  pinMode(pin_motor1, OUTPUT);   // Declarar motor 1
  pinMode(pin_motor2, OUTPUT);   // Declarar motor 2
  pinMode(pin_motor3, OUTPUT);   // Declarar motor 3
  pinMode(pin_motor4, OUTPUT);   // Declarar motor 4
  digitalWrite(pin_motor1, LOW); // Motor 1 LOW por seguridad
  digitalWrite(pin_motor2, LOW); // Motor 2 LOW por seguridad
  digitalWrite(pin_motor3, LOW); // Motor 3 LOW por seguridad
  digitalWrite(pin_motor4, LOW); // Motor 4 LOW por seguridad

  Serial.print("Encender mando RC y subir throttle al maximo");
  // Hasta no subir Throttle al maximo no salimos de este bucle while
  while (RC_Throttle_consigna > 2100 || RC_Throttle_consigna < 1900) {
    RC_Throttle_consigna = map(RC_Throttle_raw, us_min_Throttle_raw, us_max_Throttle_raw, us_min_Throttle_adj, us_max_Throttle_adj);
  }
  digitalWrite(pin_LED_rojo, LOW);
}

void loop() {
  //  Nuevo ciclo
  while (micros() - loop_timer < usCiclo);
  loop_timer = micros();

  //  Ecuaciones de procesamiento de la señal Throttle
  RC_Throttle_consigna  = map(RC_Throttle_raw, us_min_Throttle_raw, us_max_Throttle_raw, us_min_Throttle_adj, us_max_Throttle_adj);

  // La señal RC_Throttle_consigna define el tiempo que la señal PWM está en estado HIGH 
  ESC1_us = RC_Throttle_consigna;
  ESC2_us = RC_Throttle_consigna;
  ESC3_us = RC_Throttle_consigna;
  ESC4_us = RC_Throttle_consigna;

  // Para generar las 4 señales PWM, el primer paso es poner estas señales a 1 (HIGH).
  digitalWrite(pin_motor1, HIGH);  // MOTOR 1
  digitalWrite(pin_motor2, HIGH);  // MOTOR 2
  digitalWrite(pin_motor3, HIGH);  // MOTOR 3
  digitalWrite(pin_motor4, HIGH);  // MOTOR 4
  tiempo_motores_start = micros();

  // Cuando se cumpa el tiempo de PWM definido en ESCx_us, se pasa cada señal a 0 (LOW) para terminar el ciclo PWM.
  while (digitalRead(pin_motor1) == HIGH || digitalRead(pin_motor2) == HIGH || digitalRead(pin_motor3) == HIGH || digitalRead(pin_motor4) == HIGH) {
    if (tiempo_motores_start + ESC1_us <= micros()) digitalWrite(pin_motor1, LOW); // MOTOR 1
    if (tiempo_motores_start + ESC2_us <= micros()) digitalWrite(pin_motor2, LOW); // MOTOR 2
    if (tiempo_motores_start + ESC3_us <= micros()) digitalWrite(pin_motor3, LOW); // MOTOR 3
    if (tiempo_motores_start + ESC4_us <= micros()) digitalWrite(pin_motor4, LOW); // MOTOR 4
  }

  // Monitor serie
  Serial.println(RC_Throttle_consigna);
}

Esta secuencia hay que hacerla solo la primera vez que conectamos los ESC para poder configurarlos. Una vez que hemos configurado los ESC vamos a ver cómo podemos hacerlos girar en función de las órdenes recibidas del mando RC:

  1. Con el Throttle al mínimo conectar la batería y cerrar el interruptor principal para alimentar la placa Arduino y los motores
  2. Cuando se encienda el LED 13, encendemos el mando radio control.
  3. Los motores emitirán una serie de pitidos pipipi… piiiii.
  4. Terminado, podemos empezar a girar los motores con el mando radio control.
#define usCiclo 6000    // Ciclo de ejecucion de software en microsegundos (PWM)
#define pin_motor1 3    // Pin motor 1
#define pin_motor2 4    // Pin motor 2
#define pin_motor3 5    // Pin motor 3
#define pin_motor4 6    // Pin motor 4
#define pin_Throttle 8  // Pin throttle del mando RC
#define pin_LED_rojo 13 // Pin LED rojo

#include <EnableInterrupt.h>

// PWM
float ESC1_us, ESC2_us, ESC3_us, ESC4_us, loop_timer;
long tiempo_motores_start;

// AJUSTE MANDO RC - THROTLLE
float RC_Throttle_consigna;
const int us_max_Throttle_adj = 2000;
const int us_min_Throttle_adj = 950;
const float us_max_Throttle_raw = 2004; // <-- Si teneis la entrada Throttle invertida sustituid este valor
const float us_min_Throttle_raw = 1116; // <-- por este y viceversa

// INTERRUPCIÓN MANDO RC --> THROTTLE
volatile long Throttle_HIGH_us;
volatile int RC_Throttle_raw;
void INT_Throttle() {
  if (digitalRead(pin_Throttle) == HIGH) Throttle_HIGH_us = micros();
  if (digitalRead(pin_Throttle) == LOW)  RC_Throttle_raw  = micros() - Throttle_HIGH_us;
}

void setup() {

  // Decalaración de LEDs
  pinMode(pin_LED_rojo, OUTPUT);
  digitalWrite(pin_LED_rojo, HIGH);

  // Serial.begin()
  Serial.begin(115200);

  // Interrupción para canal Thrtottle
  pinMode(pin_Throttle, INPUT_PULLUP);
  enableInterrupt(pin_Throttle, INT_Throttle, CHANGE);

  // Decalaración de motores
  pinMode(pin_motor1, OUTPUT);   // Declarar motor 1
  pinMode(pin_motor2, OUTPUT);   // Declarar motor 2
  pinMode(pin_motor3, OUTPUT);   // Declarar motor 3
  pinMode(pin_motor4, OUTPUT);   // Declarar motor 4
  digitalWrite(pin_motor1, LOW); // Motor 1 LOW por seguridad
  digitalWrite(pin_motor2, LOW); // Motor 2 LOW por seguridad
  digitalWrite(pin_motor3, LOW); // Motor 3 LOW por seguridad
  digitalWrite(pin_motor4, LOW); // Motor 4 LOW por seguridad

  Serial.print("Encender mando RC y bajar Throttle al mínimo");
  // Hasta no bajar Throttle al mínimo no salimos de este bucle while
  while (RC_Throttle_consigna > 1100 || RC_Throttle_consigna < 900) {
    RC_Throttle_consigna = map(RC_Throttle_raw, us_min_Throttle_raw, us_max_Throttle_raw, us_min_Throttle_adj, us_max_Throttle_adj);
  }
  digitalWrite(pin_LED_rojo, LOW);
}

void loop() {
  //  Nuevo ciclo
  while (micros() - loop_timer < usCiclo);
  loop_timer = micros();

  //  Ecuaciones de procesamiento de la señal Throttle
  RC_Throttle_consigna  = map(RC_Throttle_raw, us_min_Throttle_raw, us_max_Throttle_raw, us_min_Throttle_adj, us_max_Throttle_adj);

  // La señal RC_Throttle_consigna define el tiempo que la señal PWM está en estado HIGH
  ESC1_us = RC_Throttle_consigna;
  ESC2_us = RC_Throttle_consigna;
  ESC3_us = RC_Throttle_consigna;
  ESC4_us = RC_Throttle_consigna;

  // Para generar las 4 señales PWM, el primer paso es poner estas señales a 1 (HIGH).
  digitalWrite(pin_motor1, HIGH);  // MOTOR 1
  digitalWrite(pin_motor2, HIGH);  // MOTOR 2
  digitalWrite(pin_motor3, HIGH);  // MOTOR 3
  digitalWrite(pin_motor4, HIGH);  // MOTOR 4
  tiempo_motores_start = micros();

  // Cuando se cumpa el tiempo de PWM definido en ESCx_us, se pasa cada señal a 0 (LOW) para terminar el ciclo PWM.
  while (digitalRead(pin_motor1) == HIGH || digitalRead(pin_motor2) == HIGH || digitalRead(pin_motor3) == HIGH || digitalRead(pin_motor4) == HIGH) {
    if (tiempo_motores_start + ESC1_us <= micros()) digitalWrite(pin_motor1, LOW); // MOTOR 1
    if (tiempo_motores_start + ESC2_us <= micros()) digitalWrite(pin_motor2, LOW); // MOTOR 2
    if (tiempo_motores_start + ESC3_us <= micros()) digitalWrite(pin_motor3, LOW); // MOTOR 3
    if (tiempo_motores_start + ESC4_us <= micros()) digitalWrite(pin_motor4, LOW); // MOTOR 4
  }

  // Monitor serie
  Serial.println(RC_Throttle_consigna);
}
 

Antes de continuar comprobad que sois capaces de gobernar los motores y que estos giran de forma controlada. Con el stick en su posición inferior los motores no se mueven, y al mover el stick los motores giran en proporción.

Os dejo un vídeo resumen para que veáis mas claro el proceso de puesta en marcha de los motores:

Arduino Drone | Controlar motores Brushless y ESC con Arduino (Code included)


Continuar con la siguiente entrada:

  1. Conceptos generales sobre drones
  2. Material necesario y montaje de los componentes hardware
  3. Mando RC y receptor. Programación en Arduino
  4. MPU6050 y su programación en Arduino
  5. Batería LiPo
  6. Control de estabilidad y PID
  7. Motores, ESC y su programación en Arduino
  8. → Calibración de hélices y motores
  9. Software completo y esquema detallado
  10. Probando el software completo antes de volar
  11. Como leer variables de Arduino en Matlab
5/5 - (8 votos)
63 Comentarios

Añadir un comentario

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