On this page, you find information and downloads for our Open Source 3D Printed Arm Robot Project called SimBot.

You will find links to the STL files to 3D print the robot parts below. From CNC Simulator Pro Version 2.0 this machine is also included as a virtual machine as well.

image

image 

You can play with it in the simulator and/or build the real machine yourself. This could make for a great student project.

image

The virtual machine can be programmed and move around just like the real one, but it cannot move parts around. 

To build the project you will need the following items:

  • An Arduino Uno for the robot controller.
  • Four robotic servos for axis X to A (can be found here).
  • One 9 gram servo for the gripper (can be found here).
  • Lots of M2 and M3 screws and nuts.
  • A 3D Printer and ABS filament.
  • A 5-8 volt power supply, 2 amps.

imageimage

Knowledge needed:

  • You need to know how to do high-quality 3D prints.
  • You need to be familiar with Arduino and its software.
  • You need to have basic soldering skills.

First of all, download the STL files for the robot here.

Print out all the parts using your 3D Printer software of choice. Use 10% infill for all parts except for the top of the base, which needs to have a 25% infill to make it a bit sturdier. Print slow enough to get nice quality. 0.2 mm or less layer height is recommended.

The base was too big for our 3D Printer so it was created in two halves. Print them out and glue them together using acetone welding.

image

Also, acetone weld the top of the base to the bottom halves.

image

Then continue by welding/ -gluing and screwing all of the remaining bits and pieces together. A Dremel tool comes in handy for drilling holes and for adjusting/cleaning up the parts.

image

Use self-locking nuts for the gripper and do not tighten the screws too much to allow for the gripper to move. Add some grease or oil to the joints. Add two short stiff metal wires between the outer gripper parts and the servo horn like the picture shows.

Run all the wires through the hole in the base and extend them if needed. Tie them together with zip ties, but be careful to allow for the full swing of the robot on all axis.

image

Now, copy and paste the Arduino firmware from the bottom of this page and use the Arduino software to program your board.

image

The axis of the robot starts with X at the base and ends with B (the gripper).

Screw the Arduino to the base plate (it goes inside the bottom of the robot base) and attach all orange servo leads (signal) as follows:

Axis X Pin 11
Axis Y Pin 10
Axis Z Pin 8
Axis A Pin 9
Axis B Pin 7

Optionally, you can add a micro switch to the gripper to tell the Arduino when to stop closing (this can protect the servo). If you choose to add the gripper switch, add one of its leads to Pin 6 of the Arduino and the other lead to the ground. Please note that when the switch is open, the Arduino should see a zero (0) on pin 6. When it is closed (the gripper is holding something) the Arduino should see a one (1) on pin 6.

image

Solder all negative (brown or black) leads together to form a common ground.

Solder all positive leads from the larger servos together. The small gripper servo should be fed from the regulated 5V of the Arduino.

Run a power cable out the back and feed it ideally with 8V, 1.5-2 amps.

 

image

 

Attach a USB cable between the computer and the Arduino.

image

A video of the robot arm in action:


The SimBot Robotic Language (SRL) is very simple.

You write GO to move in any axis. More than one axis can be programmed at once. Please note that it is a G followed by the letter O and not G0(zero), as in G-code programming.

If you add the word FAST to the end of the line the robot will move at full speed.

Example:

GO X100 Y50 A20 FAST

This line will move servo X, Y, and A (see picture above) to position 100,50 and 20.

You can also order the robot to take a pause using the PAUSE command.

Example:

PAUSE 500 

The value is in milliseconds so 500 means a half-second.

To make an endless loop of the program, add the command LOOP.

That is all there is to it at this stage!

image

Note that servos X to A are programmed from 0 to 180 degrees and the gripper servo is programmed from 0 to 90 degrees. (0 fully closed, 90 fully open)

The robot can lift small light objects only. We suggest 3D printing out small hollow cylinders in various colors that the robot can sort and move around. Have a look at the video above.

When you have all cables connected and the Arduino is programmed, you can send programs over the serial port.

The program has to start with a % character for it to be loaded to the memory of the Arduino. As the programs are stored in RAM, a maximum of 1000 bytes can be stored where each GO line takes 6 bytes (approximately 160 lines).

In CNC Simulator, go to the Serial Port settings and select the com port to which you have the Arduino connected. Also, set it to 9600 baud, 8 data bits, 1 stop bit, and no parity.

Then open the Serial Terminal (Ver 2.0 and later of CNCSimulator Pro). The Arduino will reset and you should see “SimBot Ver 1.0 ready…” in the window.

image

Now SimBot is ready to receive a program. You can use the provided demo program for your first test. Make sure that you load the arm robot with the option to load a demo program checked.

Go to the File menu and select Send Via Serial Port.

You should see “Loading…” and then the size of the loaded data when the transfer ends.

image

Now, type RUN (upper case letters) in the text box and click the Send button. Make sure that the robot has clear space to move around. Be careful so that it does not hit people or objects.

image

To stop the robot when it is running an endless loop, you can simply reset the Arduino by reconnecting the com port.

image

Please note that this is an experimental DIY project and that we only provide you with a start to continue to build upon. We invite you to improve the project by adding, for example, status LEDs, LCD display, SD-card reader, sensors, new commands, etc. We ask you to share the Arduino code by sending it to us so that others can benefit from it. Also, if you add commands for specific tasks, and we find them useful, we will add them to the interpreter of the virtual machine as well. And most important of all, remember to have fun!

/*
SimBot Firmware Ver 1.0
CNCSimulator.com


This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.


This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
GNU General Public License for more details.


For detail of the GNU General Public License see:
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;
}