Modificado el: Vie, 21 Ene, 2022 a las 4:48 PM


En esta página, encontrarás información y descargas para nuestro Proyecto de Robot de Brazo Impreso en 3D de Código Abierto llamado SimBot.


Encontrarás enlaces a los archivos STL para imprimir en 3D las partes del robot a continuación. Desde la Versión 2.0 de CNC Simulator Pro, esta máquina también está incluida como una máquina virtual.




Puede jugar con ella en el simulador y/o construir la máquina real usted mismo. Esto podría ser un gran proyecto para estudiantes.



La máquina virtual puede ser programada y moverse como la real, pero no puede mover piezas.


Para construir el proyecto necesitarás los siguientes elementos:


Un Arduino Uno para el controlador del robot.

Cuatro servos robóticos para los ejes X a A (se pueden encontrar aquí).

Un servo de 9 gramos para el agarre (se puede encontrar aquí).

Muchos tornillos y tuercas M2 y M3.

Una impresora 3D y filamento ABS.

Una fuente de alimentación de 5-8 voltios, 2 amperios.


Conocimientos necesarios:


Necesita saber cómo hacer impresiones 3D de alta calidad.

Debe estar familiarizado con Arduino y su software.

Necesita tener habilidades básicas de soldadura.


Primero, descargues los archivos STL para el robot aquí.


Imprima todas las partes usando el software de impresora 3D de su elección. Utilice un relleno del 10% para todas las partes, excepto para la parte superior de la base, que necesita tener un relleno del 25% para hacerla un poco más resistente. Imprima lo suficientemente lento para obtener una buena calidad. Se recomienda una altura de capa de 0.2 mm o menos.


La base era demasiado grande para nuestra impresora 3D, por lo que se creó en dos mitades. Imprímalas y péguelas juntas usando soldadura con acetona.



También, suelda con acetona la parte superior de la base con las mitades inferiores.



Luego continúa soldando/pegando y atornillando todas las demás piezas y partes. Una herramienta Dremel es útil para perforar agujeros y para ajustar/limpiar las piezas.



Utiliza tuercas autoblocantes para el agarre y no aprietes demasiado los tornillos para permitir que el agarre se mueva. Añade un poco de grasa o aceite a las articulaciones. Añade dos alambres metálicos cortos y rígidos entre las partes exteriores del agarre y el cuerno del servo como muestra la imagen.


Pasa todos los cables por el agujero en la base y extiéndelos si es necesario. Átalos con bridas, pero ten cuidado de permitir el movimiento completo del robot en todos los ejes.



Ahora, copia y pega el firmware de Arduino desde el fondo de esta página y usa el software de Arduino para programar tu placa.



El eje del robot comienza con X en la base y termina con B (el agarre).


Atornilla el Arduino a la placa base (va dentro de la parte inferior de la base del robot) y conecta todos los cables de servo naranjas (señal) de la siguiente manera:


Eje X Pin 11

Eje Y Pin 10

Eje Z Pin 8

Eje A Pin 9

Eje B Pin 7


Opcionalmente, puedes añadir un microinterruptor al agarre para indicarle al Arduino cuándo dejar de cerrar (esto puede proteger el servo). Si decides añadir el interruptor del agarre, conecta uno de sus cables al Pin 6 del Arduino y el otro al suelo. Ten en cuenta que cuando el interruptor esté abierto, el Arduino debería ver un cero (0) en el pin 6. Cuando esté cerrado (el agarre sostiene algo), el Arduino debería ver un uno (1) en el pin 6.



Solda todos los cables negativos (marrones o negros) juntos para formar una tierra común.


Solda todos los cables positivos de los servos más grandes juntos. El pequeño servo del agarre debe ser alimentado desde los 5V regulados del Arduino.


Pasa un cable de alimentación por la parte trasera y aliméntalo idealmente con 8V, 1.5-2 amperios.



Conecta un cable USB entre el ordenador y el Arduino.



El Lenguaje Robótico SimBot (SRL) es muy simple.


Escribes GO para mover en cualquier eje. Se pueden programar más de un eje a la vez. Ten en cuenta que es una G seguida de la letra O y no G0 (cero), como en la programación de G-code.


Si añades la palabra FAST al final de la línea, el robot se moverá a máxima velocidad.


Ejemplo:


GO X100 Y50 A20 FAST


Esta línea moverá el servo X, Y y A (ver imagen arriba) a la posición 100, 50 y 20.


También puedes ordenar al robot que haga una pausa usando el comando PAUSE.


Ejemplo:


PAUSE 500


El valor está en milisegundos, así que 500 significa medio segundo.


Para hacer un bucle infinito del programa, añade el comando LOOP.


¡Eso es todo lo que hay en esta etapa!



Ten en cuenta que los servos de la X a la A están programados de 0 a 180 grados y el servo del agarre está programado de 0 a 90 grados. (0 completamente cerrado, 90 completamente abierto.)


El robot solo puede levantar objetos pequeños y ligeros. Sugerimos imprimir en 3D pequeños cilindros huecos de varios colores que el robot pueda clasificar y mover.


Cuando tengas todos los cables conectados y el Arduino esté programado, puedes enviar programas a través del puerto serie.


El programa debe empezar con un carácter % para que se cargue en la memoria del Arduino. Como los programas se almacenan en RAM, se pueden almacenar un máximo de 1000 bytes donde cada línea GO ocupa 6 bytes (aproximadamente 160 líneas).


En CNC Simulator, ve a los ajustes del Puerto Serie y selecciona el puerto com al que tengas conectado el Arduino. Además, configúralo a 9600 baudios, 8 bits de datos, 1 bit de parada y sin paridad.


Luego, abre el Terminal Serie (Ver 2.0 y posteriores de CNC Simulator Pro). El Arduino se reiniciará y deberías ver "SimBot Ver 1.0 ready..." en la ventana.



Ahora SimBot está listo para recibir un programa. Puedes usar el programa de demostración proporcionado para tu primera prueba. Asegúrate de cargar el brazo robótico con la opción de cargar un programa de demostración activada.


Ve al menú "File" y selecciona "Send Via Serial Port".


Deberías ver "Loading..." y luego el tamaño de los datos cargados cuando termine la transferencia.



Ahora, escribe RUN (en letras mayúsculas) en el cuadro de texto y haz clic en el botón "Send". Asegúrate de que el robot tenga espacio claro para moverse. Ten cuidado de que no golpee a personas u objetos.



Para detener el robot cuando está ejecutando un bucle infinito, simplemente puedes reiniciar el Arduino reconectando el puerto com.



Por favor, ten en cuenta que este es un proyecto DIY experimental y que solo te proporcionamos un inicio para que continúes construyendo sobre él. Te invitamos a mejorar el proyecto añadiendo, por ejemplo, LEDs de estado, pantalla LCD, lector de tarjetas SD, sensores, nuevos comandos, etc. Te pedimos que compartas el código de Arduino enviándonoslo para que otros puedan beneficiarse de él. Además, si agregas comandos para tareas específicas y los encontramos útiles, también los añadiremos al intérprete de la máquina virtual. Y lo más importante de todo, ¡recuerda divertirte!


------------------------------------------------------------------------------------------------------------------------------------------


/*

SimBot Firmware Ver 1.0

CNCSimulator.com



Este programa es un software libre: puedes redistribuirlo y/o modificarlo

bajo los términos de la Licencia Pública General GNU publicada por

la Free Software Foundation, ya sea la versión 3 de la Licencia, o

(a tu elección) cualquier versión posterior.



Este programa se distribuye con la esperanza de que sea útil,

pero SIN NINGUNA GARANTÍA; sin siquiera la garantía implícita de

COMERCIABILIDAD o APTITUD PARA UN PROPÓSITO PARTICULAR. 

Consulta la Licencia Pública General GNU para más detalles.


Para detalles de la Licencia Pública General GNU, consulta:

http://www.gnu.org/licenses/ 

*/



#include <Servo.h> 



#define AXIS_X_PIN 11

#define AXIS_Y_PIN 10

#define AXIS_Z_PIN 8

#define AXIS_A_PIN 9

#define AXIS_B_PIN 7

#define GRIPPERSWITCHPIN 6



#define INDATALEN 64

#define NOTFOUND -9999

#define PROGSIZE 1000

#define FASTDELAY 10

#define SLOWDELAY 50



Servo servoX;

Servo servoY;

Servo servoZ;

Servo servoA;

Servo servoB;



char inData[INDATALEN];

byte program[PROGSIZE];

int  progindex=0;

byte index =0;

char inChar;

String theLine;

bool loadingprog=false;

unsigned long time;


int x,y,z,a,b;    // Axis positions



void setup() 

{



    servoX.attach(AXIS_X_PIN);

    servoY.attach(AXIS_Y_PIN);

    servoZ.attach(AXIS_Z_PIN);

    servoA.attach(AXIS_A_PIN);

    servoB.attach(AXIS_B_PIN);



    pinMode(GRIPPERSWITCHPIN, INPUT_PULLUP);    // Normally connected to GND (0)



    Serial.begin(9600);

    Serial.println("SimBot Ver 1.0 ready...");

}





void loop() 

{

    if(loadingprog && millis()-time > 2000)

    {

        // A program has been loaded 

        Serial.print(progindex);

        Serial.print("/");

        Serial.print(PROGSIZE);

        Serial.println(" bytes loaded.");

        loadingprog = false;

        time = millis();

    }



    if(Serial.available())

    {

        time = millis();

        inChar =Serial.read();



        if(inChar==13)

            return;



        if(loadingprog == false && inChar=='%')

        {

            // New program starts

            progindex = 0;

            loadingprog = true;

            Serial.println("Loading...");

            return;

        }



        if(progindex>=1000-7)

            return;    // No more space in buffert




  if(inChar!=10)

        {

            inData[index]=inChar;

            if(index< INDATALEN-1)

                index++;

        }

        else

        {

            int val;

            bool fast = false;

            inData[index]=0;

            if(index< INDATALEN-1)

                index++;

            index =0;

            // We have a complete line, let's interpret it.

            theLine = inData;



            if(loadingprog == false)

            {

                if(theLine.indexOf("RUN")!=-1)

                    Run();

                if(theLine.indexOf("HOME")!=-1)

                    Home();

            }

            else if(theLine.indexOf("GO")!=-1)

            {

                // GO Command found, get all axis values

                val = GetParameterValue("X", theLine);

                if(val!=NOTFOUND)

                    x=val;

                val = GetParameterValue("Y", theLine);

                if(val!=NOTFOUND)

                    y=val;

                val = GetParameterValue("Z", theLine);

                if(val!=NOTFOUND)

                    z=val;

                val = GetParameterValue("A", theLine);

                if(val!=NOTFOUND)

                    a=val;

                val = GetParameterValue("B", theLine);

                if(val!=NOTFOUND)

                    b=val;

                // Check for the FAST command

                if(theLine.indexOf("FAST")!=-1)

                    fast=true;        

                // Save the move to ram                

                if(fast)

                    program[progindex] =0;

                else

                    program[progindex] =1;

                progindex++;

                program[progindex]=x;

                progindex++;

                program[progindex]=y;

                progindex++;

                program[progindex]=z;

                progindex++;

                program[progindex]=a;

                progindex++;

                program[progindex]=b;

                progindex++;



            }

            else if(theLine.indexOf("PAUSE")!=-1)

            {

                unsigned int p = GetParameterValue(" ", theLine);



                if(p!=NOTFOUND)

                {

                    program[progindex]=3;

                    progindex++;

                    program[progindex]= (byte)lowByte(p); // p & 0x00FF;

                    progindex++;

                    program[progindex]= (byte)highByte(p); //  & 0xFF00;

                    progindex++;

                }

            }

            else if(theLine.indexOf("LOOP")!=-1)

            {

                program[progindex]=4;

                progindex++;

            }



        }

    }





}


unsigned int GetParameterValue(String axisletter, String string)

{

    int pos = string.indexOf(axisletter);



    pos++;

    while(string[pos]==' ')

        pos++;



    if(isDigit(string[pos])==false)

        return NOTFOUND;



    String num = "";

    if(pos!=-1)

    {

        while(isDigit(string[pos]))

        {

            num+=string[pos];

            pos++;

        }

    }

    else

        return NOTFOUND;



    return (unsigned int)num.toInt();

}



void Run()

{

    unsigned int d;



    Serial.println("Prog Executes.");

    int indx =0;

    while(true)

    {

        switch (program[indx])

        {

        case 0:    // GO fast

            GotoPosAll(program[indx+1],program[indx+2],program[indx+3],program[indx+4],program[indx+5],FASTDELAY);

            indx+=6;

            break;

        case 1: // GO slow

            GotoPosAll(program[indx+1],program[indx+2],program[indx+3],program[indx+4],program[indx+5],SLOWDELAY);

            indx+=6;

            break;

        case 3: // PAUSE

            d = program[indx+2] << 8;

            d |= program[indx+1];

            delay(d);

            indx+=3;

            break;

        case 4: // LOOP

            indx = 0;

            break;

        default:

            break;

        }

        if(indx>=progindex)

            break;

    }

    Serial.println("Prog Done.");

}



void GotoPosAll(byte X, byte Y, byte Z, byte A, byte B, int Delay)

{

    bool closingGripper = (sgn(B - servoB.read())==-1);



    while(true)

    {

        servoX.write(servoX.read() + sgn(X - servoX.read()));

        servoY.write(servoY.read() + sgn(Y - servoY.read()));

        servoZ.write(servoZ.read() + sgn(Z - servoZ.read()));

        servoA.write(servoA.read() + sgn(A - servoA.read()));

        if(closingGripper)

        {

            if(digitalRead(GRIPPERSWITCHPIN)==0)

                servoB.write(servoB.read() + sgn(B - servoB.read()));

        }

        else

            servoB.write(servoB.read() + sgn(B - servoB.read()));



        delay(Delay);



        if(closingGripper)

        {

            if(servoX.read()==X && servoY.read()==Y && servoZ.read()==Z && servoA.read()==A && (servoB.read()==B || digitalRead(GRIPPERSWITCHPIN)==1))

                break;

        }

        else

     {

            if(servoX.read()==X && servoY.read()==Y && servoZ.read()==Z && servoA.read()==A && (servoB.read()==B))

                break;

        }

    }

}



void Home()

{

    GotoPos(servoX, 0, 10);   

    GotoPos(servoY, 0, 10);   

    GotoPos(servoZ, 0, 10);  

    GotoPos(servoA, 0, 10); 

    GotoPos(servoB, 0, 10); 

    Serial.println("All axis at 0");

}



void GotoPos(Servo servo, int Pos, int Delay)

{

    while(Pos != servo.read())

    {

        servo.write(servo.read() + sgn(Pos - servo.read()));

        delay(Delay);

    }

}



static inline int8_t sgn(int val) {

    if (val < 0) return -1;

    if (val==0) return 0;

    return 1;

}