Robot SL FLOAT (PCB ARDU-VIC)
En este apartado quiero que nos enfoquemos en los aspectos de diseño base de SL velocista.
Para este caso estudiaremos aspectos, hipótesis y código del Robot Float que utiliza la PCB ARDU-VIC. 👈
Robot Float Diseño 3D
Este desarrollo pretende dejar conceptos y herramientas para que puedas diseñar tu robot velocista, ya sea utilizando la PCB ARDU-VIC o armado tu propia PCB.
Si vas a desarrolar tu PCB te recomiendo revisar este material:
El chasis es una parte fundamental del robot, se debe tener en cuenta:
Forma.
Tamaño.
Peso (material de construcción).
Distribución de elementos.
Distancia entre ruedas.
Distancia entre eje y sensores de lectura.
Altura con respecto al suelo.
Todos estos ítems influyen en el funcionamiento del robot.
Hay tres conceptos de chasis que considero útiles:
Modelo A - Un soporte de material liviano que contenga (PCB, sensores, motores).
Modelo B - Una PCB que sirva de chasis donde se fijen los motores.
Modelo C - Un chasis mixto, donde PCB y material liviano se ensamblen formando el chasis.
Modelo A
Modelo B
Modelo C
Observaciones:
✔️ El Modelo A, un chasis que sea de una material liviano y fácil de modelar, no podemos dejar de lado la impresión 3D por su facilidad de aplicación y modificaciones con mucha precisión.
La PCB en este caso seria sobrepuesta al chasis.
✔️ El Modelo B, un chasis que sea todo de PCB tendría la ventaja de ser liviano, pero no podríamos realizar cambios de estructura una vez construida la PCB sin tener que realizar toda la PCB nuevamente.
✔️ El Modelo C, un chasis mixto nos permite reducir espacio y peso, utilizando una pieza impresa para el acople de los sensores, que nos permite modificar el largo del robot, pero no podríamos modificar con facilidad la distancia entre motores, ya que estos están montado sobre la PCB.
Para el diseño del Robot FLOAT que utiliza una PCB (ARDU-VIC) pensada para reducir espacio entre componentes, sin contar con la sujeción de motores y sensores se trabajo con el modelo A (chasis impreso).
En este caso se realizan dos piezas impresas y la PCB va sobrepuesta:
Chasis de motores.
Chasis de sensores.
La PCB se monta sobre el chasis donde se montan los motores.
La sujeción de la PCB es con silicona, al sobreponer la pieza en el chasis se evita que la misma absorba impactos que podían dañarla.
Para la conexión de la PCB con los sensores y su alimentación, se colocan pines HDR 👈 a 90 grados en la parte inferior de la placa, para las entradas analógicas (A0...A7) y el zócalo para el módulo ministar en positivo y negativo y el GPIO D6.
La conexión entre la PCB y la regleta de sensores se hará con una tira de cables con terminales Dupont 👈 (Hembra-Hembra).
Es importante la forma del chasis y la distribución de los elementos que soporta, hay que tener en cuentas que los motores y batería son los elementos de mayor peso.
Una distribución poco eficiente provocará que el robot pierda tracción y derrape al tomar una curva con rapidez.
Se debe tratar que el centro de gravedad quede lo mas cerca al centro del eje colineal a los ejes de las ruedas (eje de tracción).
✔️ Distribución de componentes robot FLOAT en el Chasis de Motores.
🟠 Motores (distancia entre Ruedas):
Primero a la hora de ubicar los motores, tenemos que tener en cuenta la distancia entre las ruedas, por reglamento de la LNR el máximo es de 140mm entre puntas y el mínimo quedara limitado al tamaño de los motores.
Si miramos un modelo cinemático de un robot diferencial como en este caso tenemos que considerar alguno datos interesantes.
Referencias de Modelo cinemático
2L : es la distancia de separación entre las dos ruedas de tracción.
2R : es el diámetro de las ruedas.
L1 : es la distancia del centro de masa al eje de rotación de las ruedas.
☼ Si se quiere profundizar en el diseño mecánico del robot, hay que realizar el estudio del modelo cinemático de un robot diferencial.
Sin pretender realizar un estudio de la cinemática del robot en este espacio, podemos tomar datos que nos ayuden a mejorar nuestro diseño.
Para distancia entre ruedas, la formula para el calculo de la velocidad angular del robot en el modelo cinemático de esta será:
Donde:
ω = Velocidad angular del robot.
VR = Velocidad de la rueda derecha.
VL = Velocidad de la rueda izquierda.
2L = Distancia entre las ruedas.
✔️ Si la distancia entre ruedas es muy grande la velocidad angular del mismo disminuye haciendo que el robot sea lento al girar.
✔️ Por otro lado se va a necesitar una diferencia mayor en las variaciones de velocidad de los motores para girar.
La distancia entre ruedas no solo influye en la velocidad de rotación del robot.
Esta además influye en el radio mínimo de curvatura que el robot puede tomar sin necesidad de invertir el sentido de giro de uno de los motores.
Esto viene dado por la siguiente formula:
Donde:
R = radio de curvatura.
VR = Velocidad de la rueda derecha.
VL = Velocidad de la rueda izquierda.
L = Distancia entre las ruedas.
✔️ Si la velocidad de uno de los motores es 0 (caso antes de tener que invertir la velocidad) y lo aplicamos a la formula 2, nos queda que el radio mínimo de curvatura es la distancia entre ruedas (L) dividido por dos.
✔️ Por esta razón también es importante la distancia entre centros de ruedas.
🟠 Distancia entre centros de rueda robot FLOAT:
Para el diseño de el chasis posterior (chasis de motores) se tuvieron la siguientes consideraciones.
✔️ De la medida máxima por reglamento para el ancho(140mm) se descontaron 5mm para tener holgura en el reglamento, así que la distancia entre puntas de rueda es de 135mm
✔️ La distancia entre extremos de ruedas depende de el tamaño de los motores que dijimos anteriormente y también del ancho de las ruedas.
Como se utilizan unas ruedas ya existentes (28mm de ancho) se adaptó la distancia entre motores dependiendo del ancho de estas para dar la medida seleccionada de 135mm.
☑️ La distancia entre los centros de las ruedas nos queda de 107mm, por lo que teóricamente el robot podrá tomar un radio de curvatura de 53.5mm sin tener que invertir el giro de uno de los motores.
⛔ Es impórtate acá tener en cuenta lo siguiente.
El control de las RPM lo realiza el PID 👈.
La RPM del robot en linea recta esta dado por el vel_set (PWM 👈) que nosotros determinamos.
El PWM máximo para el control de las RPM de los motores es 255.
El robot viene desde una recta antes de doblar, por lo que la inercia afectara la entrada al giro.
💡 Teniendo en cuenta todos los factores mencionados anteriormente, sino queremos que un motor invierta su giro y tener en cuenta la inercia de robot, deberíamos realizar los arreglos con la programación.
Realizar muchas practicas para determinar si es mejor detener un motor al girar o dejar que PID y el control de motores invierte el giro de uno de los motores.
🟠 Distancia de los motores al final del chasis:
La distancia de los motores al final del chasis es importante a la hora de transitar por puentes y cambios de inclinación en la pista.
En la experiencia personal para evitar estos golpes y roses recomiendo lograr que la goma tape al chasis viendo el mismo lateralmente.
Como se ve en la imagen anterior, la goma tapa al chasis en la vista lateral lo que nos asegura que no existirá rosos del chasis en los puentes y cambios de inclinación.
Como ya se dijo las gomas ya se tenían en existencia, con un diámetro de 24.75mm.
Se ajusto la distancia de los motores con respeto al final del chasis para tener como mínimo un despeje de 1mm entre la goma y el mismo.
Despeje del robot es de 1.26mm.
🟠 Selección de motores y ruedas:
El diseño del robot es fundamental para la selección de los motores, es necesario considerar el peso del robot y el diámetro de las gomas para la selección de estos.
En este caso los motores a utilizar son los disponibles en el mercado:
El robot utiliza motorreductores de 3000 rpm 6V (similares a los POLOLU 👈).
Motorreductor 10:1
El diámetro de las ruedas ya esta determinado 24.75mm, vamos a tomar 24.5mm, el radio (12.25mm) va influir en la velocidad máxima del robot y el torque para mover el robot con una aceleración que determinemos.
En el caso que las ruedas las fabriquemos nosotros a medida, es importante contemplar que con mas radio la velocidad final del robot será mayor, pero el torque se vera disminuido y viceversa.
(El material que se utilizo para las gomas es caucho de silicona D20).
Para calcular el torque necesario del motor necesitamos saber:
Masa total del robot.
Radio de la rueda.
Aceleración deseada.
Donde:
T = Torque del motor [Nm].
m = masa total del robot [Kg].
a = aceleración deseada [m/s^2 ].
g = fuerza de gravedad [m/s^2 ].
φ = ángulo del plano.
r = radio de la goma [m].
✔️ Para este robot tomare la experiencia personal, por lo que doy por sentado que el torque de los motores seleccionados y el radio de las gomas, es suficiente para poder acelerar al robot a mas de 2 m/s^2.
✔️ Dejo la formula anterior para que puedas realizar tus cálculos.
🟠 Velocidad máxima del robot:
¿ Que velocidad máxima puede alcanzar nuestro robot teóricamente?.
Tenemos que tener en cuenta algunos factores de este calculo teórico:
La velocidad máxima cuando los dos motores reciben un PWM de 255.
Que los motores no tenga rendimientos diferentes de RPM (algo muy poco probable).
El diámetro de la rueda (la medida usada para el calculo puede no ser precisa por la deformación de la goma).
Como se dijo anteriormente el calculo de velocidad máxima es teórico y se aplica la siguiente formula:
Donde:
v = Velocidad del robot [m/s].
V RPM = revoluciones máxima del motor [RPM].
r = radio de la goma [m].
En el caso del robot FLOAT la velocidad máxima teórica que podría alcanzar seria:
✔️ La velocidad teórica máxima calculada es considerablemente alta para un robot sin turbina, esto no deja la posibilidad de reducir el diámetro de la goma par aganar aceleración perdiendo algo de velocidad final que no se podría alcanzar sin tener dificultades con la inercia en las curvas.
🟠 Distancia de sensores al eje de los motores:
Con respecto a los sensores hay mucha información, se puede armar la regleta de sensores o utilizar una ya armada, como en este caso.
Se utiliza una regleta con distribución lineal de 8 sensores QRD1114.
Independientemente del tipo diseño adoptado (Modelo A, B, C) la distancia entre los sensores y el eje de la rueda es muy importante, ya que le permitirá al controlador ver con anticipación la curva.
Si la distancia es muy grande el robot tendrá problemas para tomar las curvas mas cerradas, si las curvas son amplias convendría tener una distancia mayor. (recordando que máximo actual por reglamente en LNR es de 200mm).
✔️ Con el tiempo he probado diferentes relaciones obteniendo resultados aceptables con distancias que van de 160mm a 140mm.
✔️ Por lo que aquí es donde las pruebas de funcionamiento del robot son muy importantes.
La distancia de los sensores al eje de tracción es de 156.6 mm, esta se vera acortada algunos milímetros al curvar el chasis.
🟠 Distancia de batería y PCB con respecto al final del chasis:
Como se comento anteriormente es importante tener el centro de masa lo mas cerca posible al eje colineal a la tracción.
Los elementos pesados como la batería deberían colocarse lo mas cercano a este, en algunos casos se la coloca arriba de los motores.
✔️ Para este diseño se coloco el soporte de batería 5mm elevado del chasis para poder pasar los cables de alimentación para los motores por debajo de este.
Este soporte puede suprimirse si se utiliza para la sujeción velcro.
✔️ La PCB se coloco de manera que fuera sencillo la conexión de los cables de alimentación.
⛔ El objetivo del robot FLOAT es implementar la PBC ARDU-VIC y la regleta de sensores QRD1114 x 8 para la adquisición de datos y mejora de código.
⛔ Si se realizan mejoras con respecto al diseño se agregaran a:
✅ Con la implementación de este diseño el robot sin batería pesa 138 gr.
Para poder comenzar con la generación del código del robot en el IDe de ARDUINO, debemos contar con la tabla de GPIOs.
En la misma detallaremos:
Tipo de Señal (Digital - Analógica - PWM).
Modo (Entrada - Salida).
Pin de ARDUINO NANO.
Componente a cual se conecta.
Pin de conexión en el componente.
El código base para ARDUINO esta completo para el funcionamiento del robot FLOAT utilizando la PCB ARDU-VIC.
Se deja también el link de los videos explicativos del código desde cero, además de las mejoras posibles para el control:
Uso de dip switch para cambios del programa.
Organización del código.
Aceleración en recta.
/*Código base Robot FLOAT 24*/
/* www.alosibots.com */
/*Procesador ATmega 382P*/
/*Set de parámetros de control*/
// Ciclo de trabajo PWM
int vel_set = 0;
// Constantes PID
float KP = 0.5;
float KD = 1.5;
float KI = 0.0001;
/*Etiquetas de pines*/
/*Pulsador de arranque*/
#define PUL 2
/*Indicadores led - Regleta*/
#define LED 13
#define IR 6
/*Driver*/
#define PWMA 3
#define AIN1 5
#define AIN2 4
#define PWMB 11
#define BIN1 7
#define BIN2 8
/*Dip switch*/
#define DIP1 12
#define DIP2 10
#define DIP3 9
/*Sensores QTR8*/
/*mirando el robot de atras*/
#define S1 A7 //derecho
#define S2 A6
#define S3 A5
#define S4 A4
#define S5 A3
#define S6 A2
#define S7 A1
#define S8 A0 //izquierdo
/*Creacion de varibles*/
/*Lectura de sensores*/
int LS1 = 0;
int LS2 = 0;
int LS3 = 0;
int LS4 = 0;
int LS5 = 0;
int LS6 = 0;
int LS7 = 0;
int LS8 = 0;
/* Variable poscicion relativa*/
float ponderacion = 0;
float suma_lecturas = 0;
float pos_rel = 0;
int error = 0;
/* VARIABLES CONTROL */
int izq = 0;
int der = 0;
int vel = 0;
int P = 0;
int D = 0;
int I = 0;
int EA = 0;
void setup() {
/*Configuracion de pines*/
pinMode(PUL, INPUT);
pinMode(LED,OUTPUT);
pinMode(IR,OUTPUT);
pinMode(AIN1,OUTPUT);
pinMode(AIN2,OUTPUT);
pinMode(BIN1,OUTPUT);
pinMode(BIN2,OUTPUT);
// Incio monitor serial
Serial.begin(9600);
/*Activacion de Regleta (LOW-OFF / HIGH-ON)*/
digitalWrite(IR,HIGH);
} // fin setup
void loop() {
digitalWrite(LED,HIGH);
// pulsador sin pulsar el código se detiene aquí
while (digitalRead(PUL)==0);
// pulsador pulsado esperando para largar
while (digitalRead(PUL)){
digitalWrite(LED,LOW);
}
digitalWrite(LED,HIGH);
// bucle infinito
while (true) {
promedio_ponderado();
control();
motores(izq,der);
}
} // fin loop
void motores (int VmIzq, int VmDer) {
/*Dirección Motor derecho mirando desde atrás*/
if (VmDer >= 0) {
digitalWrite(AIN1,LOW);
digitalWrite(AIN2,HIGH);
}
else {
digitalWrite(AIN1,HIGH);
digitalWrite(AIN2,LOW);
VmDer = VmDer * -1;
}
/*Dirección Motor Izquierdo mirando desde atrás*/
if (VmIzq >= 0) {
digitalWrite(BIN1,HIGH);
digitalWrite(BIN2,LOW);
}
else {
digitalWrite(BIN1,LOW);
digitalWrite(BIN2,HIGH);
VmIzq = VmIzq * -1;
}
analogWrite(PWMA,VmDer); // PWM del micro para motor izq.
analogWrite(PWMB,VmIzq); // PWM del micro para motor der.
} // fin control de motores
void promedio_ponderado() {
// Lectura de sensores //
LS1 = analogRead(S1); // sensor extremo derecho
LS2 = analogRead(S2);
LS3 = analogRead(S3);
LS4 = analogRead(S4);
LS5 = analogRead(S5);
LS6 = analogRead(S6);
LS7 = analogRead(S7);
LS8 = analogRead(S8); // sensor extremo izquierdo
/* Mapeo de lecturas */
LS1 = map(LS1, 0,1023,1000,0);
LS2 = map(LS2, 0,1023,1000,0);
LS3 = map(LS3, 0,1023,1000,0);
LS4 = map(LS4, 0,1023,1000,0);
LS5 = map(LS5, 0,1023,1000,0);
LS6 = map(LS6, 0,1023,1000,0);
LS7 = map(LS7, 0,1023,1000,0);
LS8 = map(LS8, 0,1023,1000,0);
/*calculos de posicion relativa*/
ponderacion = ((LS1*0)+(LS2*1)+(LS3*2)+(LS4*3)+(LS5*4)+(LS6*5)+(LS7*6)+(LS8*7));
suma_lecturas = (LS1+LS2+LS3+LS4+LS5+LS6+LS7+LS8);
pos_rel = 1000*(ponderacion/suma_lecturas);
error = pos_rel - 3500;
} // fin promedio ponderado
void control() {
digitalWrite(LED, HIGH);
/*salida por derecha*/
if(error > 1350) {
while(error > 600){
digitalWrite(LED, LOW);
motores(-150,200);
promedio_ponderado();
}
}
/*salida por izquierda*/
if(error < -1350) {
while(error < -600){
digitalWrite(LED, LOW);
motores(200,-150);
promedio_ponderado();
}
}
P = error; // proporcional
D = P - EA; // calculo derivado
I = I + EA; // calculo integral
EA = P; // Error anterior igual al actual
/*Limite de integral*/
if (I >= 1000) {
I = 1000;
}
if (I <= -1000) {
I = -1000;
}
vel = (P*KP) + (D*KD) + (I*KI); // calculo vel ajuste con PID
izq = vel_set - vel; // ajuste de velocidad izq
der = vel_set + vel; // ajuste de velocidad der
/*Limite de velocidad a max PWM*/
if (izq >= 255) {
izq = 255;
}
if (izq <= -255) {
izq = -255;
}
if (der >= 255) {
der = 255;
}
if (der <= -255) {
der = -255;
}
}// fin control
void monitorserie() {
/* Muestra de valores en monitor serial */
Serial.print(" | ");
Serial.print("◄"); Serial.print(" | ");
Serial.print("◄"); Serial.print(" | ");
Serial.print("◄"); Serial.print(" | ");
Serial.print("▲"); Serial.print(" | ");
Serial.print("▲"); Serial.print(" | ");
Serial.print("►"); Serial.print(" | ");
Serial.print("►"); Serial.print(" | ");
Serial.print("►"); Serial.println(" | ");
Serial.print(" | ");
Serial.print("A0"); Serial.print(" | ");
Serial.print("A1"); Serial.print(" | ");
Serial.print("A2"); Serial.print(" | ");
Serial.print("A3"); Serial.print(" | ");
Serial.print("A4"); Serial.print(" | ");
Serial.print("A5"); Serial.print(" | ");
Serial.print("A6"); Serial.print(" | ");
Serial.print("A7"); Serial.println(" | ");
Serial.print(" | ");
Serial.print(analogRead(S8)); Serial.print(" | ");
Serial.print(analogRead(S7)); Serial.print(" | ");
Serial.print(analogRead(S6)); Serial.print(" | ");
Serial.print(analogRead(S5)); Serial.print(" | ");
Serial.print(analogRead(S4)); Serial.print(" | ");
Serial.print(analogRead(S3)); Serial.print(" | ");
Serial.print(analogRead(S2)); Serial.print(" | ");
Serial.print(analogRead(S1)); Serial.println(" | ");
Serial.print(" | ");
Serial.print(LS8); Serial.print(" | ");
Serial.print(LS7); Serial.print(" | ");
Serial.print(LS6); Serial.print(" | ");
Serial.print(LS5); Serial.print(" | ");
Serial.print(LS4); Serial.print(" | ");
Serial.print(LS3); Serial.print(" | ");
Serial.print(LS2); Serial.print(" | ");
Serial.print(LS1); Serial.println(" | ");
delay(500);
/* Muestra de valores calculados posicion relativa*/
Serial.println();
Serial.print("ponderacion = ");Serial.println(ponderacion);
Serial.print("suma = ");Serial.println(suma_lecturas);
Serial.print("pos_rel = ");Serial.println(pos_rel);
Serial.print("Error = ");Serial.println(error);
Serial.println();
} // fin monitorserie
🟦 Chasis de motores:
Cuando se realiza el ensamble del robot se retiro un travesaño del chasis de los motores para que los cables de alimentación y activación para la regleta pudieran colocare.
🟦 Curvatura de Chasis:
Para no tener inconvenientes con los puentes, se realiza una curvatura en el chasis para no tener rozamientos con los cambios de inclinación de los puentes.