How to Build an Arduino Self-Balancing Robot

By Roland Pelayo

Ever wonder how Segways work? This tutorial will show you how to build an Arduino self-balancing robot that balances itself — just like a Segway!

How Does Balancing Work?

To keep the robot balanced, the motors must counteract the fall of the robot. This action requires a feedback and a correcting element. The feedback element is the MPU6050 gyroscope + accelerometer, which gives both acceleration and rotation in all three axis (MPU6050 I2C basics) which is used by the Arduino to know the current orientation of the robot. The correcting element is the motor and wheel combination.

Required Materials

  • Arduino (UNO or Nano can be used. I used Nano for this project.)
  • MPU6050 gyro+accelerometer breakout board.
  • L298N driver module
  • 2 x Geared DC Motor+wheels
  • Three platforms (PCB, acrylic, or thick plastic)
  • Posts to hold the platforms
  • Jumper wires
  • Headers
  • Battery Pack

 

Connection Diagram

Complete Fritzing diagram

Connect the MPU6050 to the Arduino first and test the connection using the codes in this IMU interfacing tutorial.  If data is now displayed on the serial monitor, you’re good to go! Proceed to connect the rest of the components as shown above.

The L298N module can provide the +5V needed by the Arduino as long as its input voltage is +7 V or greater.  However, I chose to have separate power sources for the motor and the circuit for isolation. Note that if you are planning to use a supply voltage of more than +12V for the L298N module, you need to remove the jumper just above the +12V input.

Building the Robot

Robot frame (made mostly of acrylic slab) with two geared dc motors

Main circuit board consisting of an Arduino Nano and MPU6050

L298N motor driver module

Geared DC motor with wheel

 

The self-balancing robot is essentially an inverted pendulum. It can be balanced better if the center of mass is higher relative to the wheel axles. A higher center of mass means a higher mass moment of inertia which corresponds to lower angular acceleration (slower fall). This is why I’ve placed the battery pack on top. The height of the robot, however, was chosen based on the availability of materials.

Completed self-balancing robot. At the top are six Ni-Cd batteries for powering the circuit board. In between the motors is a 9V battery for the motor driver.

 

More Self-balancing Theories

In control theory, keeping some variable (in this case, the position of the robot) steady needs a special controller called a PID: P for proportional, I for integral, and D for derivative. Each of these parameters has “gains” normally called Kp, Ki, and Kd.

PID provides correction between the desired value (or input) and the actual value (or output). The difference between the input and the output is called “error”. The PID controller reduces the error to the smallest value possible by continually adjusting the output. In our Arduino self-balancing robot, the input (which is the desired tilt, in degrees) is set by software. The MPU6050 reads the current tilt of the robot and feeds it to the PID algorithm which performs calculations to control the motor and keep the robot in the upright position.

PID requires that the gains Kp, Ki, and Kd values be “tuned” to optimal values. Engineers use software like MATLAB to compute these values automatically. Unfortunately, we can’t use MATLAB in our case because it would further complicate the project. We will tune the PID values manually instead. I’ve outlined the steps on how to do this:

    1. Make Kp, Ki, and Kd equal to zero.
    2. Adjust Kp. Too little Kp will make the robot fall over (not enough correction). Too much Kp will make the robot go back and forth wildly. A good enough Kp will make the robot slightly go back and forth (or oscillate a little).
    3. Once the Kp is set, adjust Kd. A good Kd value will lessen the oscillations until the robot is almost steady.  Also, the right amount of Kd will keep the robot standing even if pushed.
    4. Lastly, set the Ki. The robot will oscillate when turned on even if the Kp and Kd are set but will stabilize in time. The correct Ki value will shorten the time it takes for the robot to stabilize.

 

Arduino Self-balancing Robot Code

I needed four external libraries to make this Arduino self-balancing robot work. The PID library makes it easy to calculate the P, I, and D values. The LMotorController library is used for driving the two motors with the L298N module. The I2Cdev library and MPU6050_6_Axis_MotionApps20 library are for reading data from the MPU6050. You can download the code including the libraries in this repository.

#include <PID_v1.h>
#include <LMotorController.h>
#include "I2Cdev.h"
#include "MPU6050_6Axis_MotionApps20.h"

#if I2CDEV_IMPLEMENTATION == I2CDEV_ARDUINO_WIRE
 #include "Wire.h"
#endif

#define MIN_ABS_SPEED 20

MPU6050 mpu;

// MPU control/status vars
bool dmpReady = false; // set true if DMP init was successful
uint8_t mpuIntStatus; // holds actual interrupt status byte from MPU
uint8_t devStatus; // return status after each device operation (0 = success, !0 = error)
uint16_t packetSize; // expected DMP packet size (default is 42 bytes)
uint16_t fifoCount; // count of all bytes currently in FIFO
uint8_t fifoBuffer[64]; // FIFO storage buffer

// orientation/motion vars
Quaternion q; // [w, x, y, z] quaternion container
VectorFloat gravity; // [x, y, z] gravity vector
float ypr[3]; // [yaw, pitch, roll] yaw/pitch/roll container and gravity vector

//PID
double originalSetpoint = 173;
double setpoint = originalSetpoint;
double movingAngleOffset = 0.1;
double input, output;

//adjust these values to fit your own design
double Kp = 50;   
double Kd = 1.4;
double Ki = 60;
PID pid(&input, &output, &setpoint, Kp, Ki, Kd, DIRECT);

double motorSpeedFactorLeft = 0.6;
double motorSpeedFactorRight = 0.5;
//MOTOR CONTROLLER
int ENA = 5;
int IN1 = 6;
int IN2 = 7;
int IN3 = 8;
int IN4 = 9;
int ENB = 10;
LMotorController motorController(ENA, IN1, IN2, ENB, IN3, IN4, motorSpeedFactorLeft, motorSpeedFactorRight);

volatile bool mpuInterrupt = false; // indicates whether MPU interrupt pin has gone high
void dmpDataReady()
{
 mpuInterrupt = true;
}


void setup()
{
 // join I2C bus (I2Cdev library doesn't do this automatically)
 #if I2CDEV_IMPLEMENTATION == I2CDEV_ARDUINO_WIRE
 Wire.begin();
 TWBR = 24; // 400kHz I2C clock (200kHz if CPU is 8MHz)
 #elif I2CDEV_IMPLEMENTATION == I2CDEV_BUILTIN_FASTWIRE
 Fastwire::setup(400, true);
 #endif

 mpu.initialize();

 devStatus = mpu.dmpInitialize();

 // supply your own gyro offsets here, scaled for min sensitivity
 mpu.setXGyroOffset(220);
 mpu.setYGyroOffset(76);
 mpu.setZGyroOffset(-85);
 mpu.setZAccelOffset(1788); // 1688 factory default for my test chip

 // make sure it worked (returns 0 if so)
 if (devStatus == 0)
 {
 // turn on the DMP, now that it's ready
 mpu.setDMPEnabled(true);

 // enable Arduino interrupt detection
 attachInterrupt(0, dmpDataReady, RISING);
 mpuIntStatus = mpu.getIntStatus();

 // set our DMP Ready flag so the main loop() function knows it's okay to use it
 dmpReady = true;

 // get expected DMP packet size for later comparison
 packetSize = mpu.dmpGetFIFOPacketSize();
 
 //setup PID
 pid.SetMode(AUTOMATIC);
 pid.SetSampleTime(10);
 pid.SetOutputLimits(-255, 255); 
 }
 else
 {
 // ERROR!
 // 1 = initial memory load failed
 // 2 = DMP configuration updates failed
 // (if it's going to break, usually the code will be 1)
 Serial.print(F("DMP Initialization failed (code "));
 Serial.print(devStatus);
 Serial.println(F(")"));
 }
}


void loop()
{
 // if programming failed, don't try to do anything
 if (!dmpReady) return;

 // wait for MPU interrupt or extra packet(s) available
 while (!mpuInterrupt && fifoCount < packetSize)
 {
 //no mpu data - performing PID calculations and output to motors 
 pid.Compute();
 motorController.move(output, MIN_ABS_SPEED);
 
 }

 // reset interrupt flag and get INT_STATUS byte
 mpuInterrupt = false;
 mpuIntStatus = mpu.getIntStatus();

 // get current FIFO count
 fifoCount = mpu.getFIFOCount();

 // check for overflow (this should never happen unless our code is too inefficient)
 if ((mpuIntStatus & 0x10) || fifoCount == 1024)
 {
 // reset so we can continue cleanly
 mpu.resetFIFO();
 Serial.println(F("FIFO overflow!"));

 // otherwise, check for DMP data ready interrupt (this should happen frequently)
 }
 else if (mpuIntStatus & 0x02)
 {
 // wait for correct available data length, should be a VERY short wait
 while (fifoCount < packetSize) fifoCount = mpu.getFIFOCount();

 // read a packet from FIFO
 mpu.getFIFOBytes(fifoBuffer, packetSize);
 
 // track FIFO count here in case there is > 1 packet available
 // (this lets us immediately read more without waiting for an interrupt)
 fifoCount -= packetSize;

 mpu.dmpGetQuaternion(&q, fifoBuffer);
 mpu.dmpGetGravity(&gravity, &q);
 mpu.dmpGetYawPitchRoll(ypr, &q, &gravity);
 input = ypr[1] * 180/M_PI + 180;
 }
}

My Kp, Ki, Kd values may or may not work you. If it doesn’t, then follow the steps I outlined above. Notice that the input tilt in my code is set to 173 degrees. You can change this value if you’d like but take note that this is the tilt angle to which the robot must be maintained.

Also, if your motors are too fast, you can adjust the motorSpeedFactorLeft and motorSpeedFactorRight values.

Video

Here’s the self-balancing robot in action!

What’s Next?

An improvement for this self-balancing robot would be controlling it remotely. Unfortunately, I can’t make this robot do that unless I make it ultra stable using dc motors with an encoder. An encoder would update the current speed of the motor which I can use to make the robot steadier via a second PID loop. I might do that next time so stay tuned!

Your Arduino Balancing Robot (YABR)

Your Arduino Balancing Robot (YABR) is a self-balancing robot that you can build yourself as a school project or as a fun project with your kids. It might look simple but there is a lot that you can learn from building this self-balancing robot.

In contrast to most self-balancing robots, this one uses stepper motors instead of regular DC motors. The main reason is that stepper motors are precise and have no performance loss when the battery voltage drops. One pulse is always an exact amount of motion. Regular DC motors can have mechanical friction and electric resistance differences. This can cause performance differences. As a result the robot will not move in a straight line.

The total cost to build this robot is approximately $80 if you use the hardware list below. This includes a battery, Nunchuck, charger, stepper motors, etc.

The Arduino program that you can download for free is 100% self-written and not based on any other software. The code is well commented and clearly explained. This makes it possible to further develop the code for your own purpose.

 Click to see the full image

If you encounter any problems during the build or setup please check the Q&A page first. Most questions are already answered in detail.

Step 1 – Software

First download the complete YMFC-AL software package:

YABR.zip (version 1.1)

Step 2 – Hardware

To build this robot you need hardware. I made the following list for convenience purpose alone. You are free to get your own hardware from different sources. But this is the hardware that I used/ordered:

If the 35mm stepper motors are out of stock. You could also use these stepper motors. Please note that these are 42mm in stead of 35mm. So you have to modify the frame.

Most of the following parts can be found in your local electronics store. But in case you don’t have an electronics store nearby I will put links here:

And finally you need an old inner tube and two sheets of plywood. I used 2.5mm and 12.5mm sheets.

Step 3 – Tools

And of course you need some simple tools like a soldering iron, screwdrivers, a fretsaw, compact drill, etc.

Step 4 – The build

Watch the YABR hardware build video and build the robot according to the video and the schematic that is included in the complete software package.

Building the YABR balancing robot.

Detailed pictures of my own YABR balancing robot can be found in the media section of this project page.


4.1 The diode and resistors


The resistor R1 on the schematic is needed for uploading a program to the Arduino. The TXD output of the transceiver is forced high or low. As a result the FTDI programmer cannot change this output anymore and you will get an upload error. By adding this resistor the FTDI programmer can change the voltage on the RX-pin of the Arduino despite the state the transceiver output and the program is uploaded without any problems.

The other two resistors (R2 and R3) form a voltage divider. Meaning that the 12.6 volt of the battery minus the 0.6 volt voltage drop over the diode is divided by 2.5. Resulting in a 4.8 volt on the analog input when the battery fully charged. In the main program this analog input will be used to protect the battery. This is because lipo batteries can be damaged when the voltage drops below 3 volt per cell.

The diode D1 protects all the electronics against reversed polarity. So when you accidentally reverse the connections of the battery the components won’t go up in smoke.


4.2 The MPU-6050 gyro/accelerometer


The only gyro / accelerometer that is supported by the YABR software is the MPU-6050. This is because the self-level feature requires an accelerometer and a gyro as I explain in these two videos:

MPU-6050 6dof IMU tutorial for auto-leveling quadcopters – Part 1
MPU-6050 6dof IMU tutorial for auto-leveling quadcopters – Part 2

The orientation of the gyro is important. Make sure to mount the gyro in the exact same orientation as shown on this picture. Otherwise the YABR software cannot calculate the correct angle and the robot will not work.


4.3 Hardware test


Please note that you are soldering the wires on the back side of the PCB. The schematic is drawn facing the components from the front. So everything is mirrored and you need to double check all the connections before you connect any power to the PCB.

With everything in place it’s time to connect the FTDI programmer to the Arduino pro mini. Don’t connect the battery yet. If the LED’s don’t lit up there is a short circuit in the wiring and you need to disconnect the FTDI programmer as soon as possible. Normally the Arduino pro mini is already programmed with the blink sketch so the LED on the Arduino should start to flash.

To check if the gyro is connected correctly and to check the balancing point of the robot you need to upload the “hardware-check” program that you can find in the software package that you downloaded earlier.

Test the balancing angle of the robot and fix it in that position on a stand as I showed in the video. Upload the “hardware-check” program, open the serial monitor and set the baud rate to 9600.

After uploading the program, open the serial monitor and set the baud rate to 9600.

The program will check if there is any I2C device is connected and if this is a MPU-6050. If everything is working as expected the program will output several raw gyro values on the screen. These are just examples and your values may be different. Note down the balance value that you see in the serial output. You will need it later in the main program.


4.4 Limit the motor current


Next thing on the to do list is to set the stepper controllers to the correct drive current. If the motor current is set to high the stepper controllers will heat up and they might get damaged.

First set the potentiometer at the same position as shown in the picture below. Now always be careful when connecting the lipo battery for the first time. A short circuit can cause high currents, heat, sparks, and burns.

A good alternative is to use a small DC fuse like the one below. This fuse will blow if the wiring on the back side of the pcb holds a short circuit.

The easiest and safest way to set the correct current and to check if the wiring is correctly connected is by measuring the current in the power supply wires with a bench power supply. The power supply is limited to 500milli amps. This is an extra safety feature. If there is a short circuit the power supply will limit the current to 500 milli amps and the wiring will be fine.

First connect one motor. With the potentiometer it’s possible to set the current between 100 and 150mA. This is more than enough to get good performance. Do the same with the other stepper controller.

If you don’t have the possibility to measure the current just set the potentiometer in this position and feel if the stepper driver doesn’t get to hot. But it’s always best to measure the current.


3.5 The remote control


If you open the Nunchuck you can note the wire colors that are connected to the various pins as you can see on the schematic. The Nunchuck works on 3.3V and you can use the 3.3V output of the Arduino Uno to power the Nunchuck.

The 5V output can be used for the transceiver. Again, connect the wires as shown on the schematic to get it to work.

To check if the Nunchuck is connected correctly you need to upload the “hardware-check” program that you can find in the software package that you downloaded earlier. After uploading the program, open the serial monitor and set the baud rate to 9600.

The program will check if there is any I2C device is connected and if this is a Nunchuck. If everything is working as expected the program will output several raw joystick values on the screen.

Step 5 – Upload the software

And finally you can upload the YABR-remote program to the Arduino Uno and the YABR-robot program to the Arduino pro mini.

The YABR-remote program does not need any modification. In the robot program you need to change the accelerometer calibration value to the value that was shown by the hardware test program when the robot was in it’s balancing position.

To start the robot you need to power up the remote. Lay the robot on it’s back and switch on the power. The LED will blink indicating that the gyro is calibrating. When the blinking stops you can slowly lift the robot and it will automatically start to balance itself.

And basically that’s it. You can now control the robot with the Nunchuck.

B-Robot EVO 2 KIT (Plug and Play Robot version)

JJrobots´s B-ROBOT EVO 2 Kit. Created to simplify the set up and integration of all the different devices involved in this project.

This COMPLETE VERSION includes all the electronic and hardware components required to create the B-Robot. You just need to assemble everything  (optional 3D parts)

What you get when you buy this KIT:

  •  jjRobots Brain Shield 
  •  Arduino Leonardo (CLONE) + USB cable (already programmed)
  •  2x High Quality NEMA17 stepper motors +14 cms cables (pair)
  •  2x Stepper motor driver
  •  IMU (gyro+accelerometers) + custom cable
  • Powerful servo: Metal gears (you will need an arm to fight and raise your B-robot…)
  • 6x AA Battery case with ON/OFF Switch  (batteries not included)
  • Bolts+nuts needed to set everything up
  • Pair of nylon bumpers (14×5 cms)
  • Double side tape, googly eyes…
  • Optional: 3D printed parts

NEW: control your B-robot using the JJrobots FREE APP! (Android devices) or the Roverbot APP (for iOS phones. not official)

new B-ROBOT Evo 2 FEATURES:

    • STEM education robot: perfect introduction to a robot that solves the inverted pendulum problem. Modify the B-robot EVO 2 as much as you can (both the robot parts themselves or its code) while you have fun!
    • Control it using your smartphone/tablet via the free jjRobots APP
    • Google Blockly controllable!
    • Perfect to have fun as you learn robotics (Take a look to the Robotics Challenges!)
    • Now can use regular AA batteries (or a 3 cells LIPO battery)
    • Two SERVO outputs (one used for the ARM). Both can be controlled from the jjRobots APP
    • Easier to print and using less plastic
    • PRO MODE can be activated from your smartphone/Tablet (increased agility and velocity)
    • Increased WIFI range (up to 40 meters)
    • Battery status
    • “Tilt angle” displayed in real time on your smartphone screen

 

logo GOOGLE PLAY v2

 

Personalise your B-robot to fight, create your own weapons, increase the size of the wheels… it is up to you! Take a look to some parts (and send us yours!)
Customise your own bumper using the online tool at Thingiverse 

 

B-ROBOT Evo 2 Features:

  • STEM education robot.  In addition to being fun, the B-robot EVO 2 engage beginners and advanced students and incorporate many of the fundamental STEM concepts providing a learning platform that everyone enjoys
  • Control it using your smartphone/tablet using the free jjRobots APP
  • Google Blockly controllable
  • Perfect have fun as you learn about robotics (Take a look to the Robotics Challenges!)
  • Open Robot project: code and 3D design files are open and shared. You could personalise your robot as much as you want.
  • DIY & Hackeable: BROBOT is not a closed final product, BROBOT is an open, modifiable and hackeable platform, perfect to learn and play as much as you want!
  • Develop your own apps: You could modify the source code of BROBOT to perform new tasks but the communication protocol is also open so you can develop your own IOS, Android, PC remote apps to control your BROBOT!
  • Learn: BROBOT is a JJROBOTS product and this mean that you will receive a well documented project (source code and external documentation). We want you know all that is happening inside your Robot! This is ideal for learning and teaching technology. We will provide very good documentation. How we are controlling the motors, how we read and integrate the information from gyros and accelerometers, how we are controlling de stability of the robot, how we communicate with the control apps, etc…

– Build with your kids, at school, for yourself… this is a unique gadget. A perfect STEM education robot

– This self balancing robot has a medium size, perfect to carry your own beer (or mineral water ;-))

– There is a community behind BROBOT so you will have a forum to ask questions, share your experiences, MODs/ Hacks and contact other users…

– You can use these self balancing robot parts to create more robots or gadgets, keep in mind all the devices used in a BROBOT are standard electronic devices with a lot of potential. In the JJROBOTS community we want to show you how! You are now buying a self balancing robot, you are buying your a versatile set of electronics and ancillary devices.

 

B-Robot EVO 2. Much more than a self balancing robot

 

 


REMOTELY CONTROL YOUR B-ROBOT EVO

 

Control and tune-up your B-robot from your own smartphone/ tablet using the Control APP (freely available on Google play).

Modify its PID robotic control in real time and see how that affects to its behaviour and performance.

The new version displays the battery status and robot´s tilt angle in real time. Control the two servo output just tapping on the screen.

 

 

 

HAVE FUN LEARNING ROBOTICS

Learn Robotics and have fun with the STEM Challenges!

How does this robot work? Can I adjust its behaviour? And modify it?

STEM education robot:  In addition to being fun, the B-robot EVO 2 engage beginners and advanced students and incorporate many of the fundamental STEM concepts providing a learning platform that everyone enjoys

Bring a beverage can to the other side of the room not dropping it, race against other B-robots with different configurations and add-ons and understand what it is going on. The B-robot EVO 2 is a very versatile and fun STEM learning robot

CUSTOMISE YOUR ROBOT!

Create your own bumpers and personalise your B-robot with the online customisation tool on Thingiverse

 

USEFUL LINKS

B-Robot EVO 2 Assembly guide

Better than a bunch of photos we have created an Assembly guide video. Some steps, like how to program the Arduino, controlling your robot or Troubleshooting are listed below. The interactive 3D model will help you to get a good idea about how the B-robot EVO looks.

Part list:
  •  jjRobots Brain Shield  (or equivalent: schematic info here)
  •  Arduino Leonardo (CLONE) + USB cable (already programmed)
  •  2x High Quality NEMA17 stepper motors +14 cms cables (pair)
  •  2x Stepper motor driver
  •  IMU (gyro+accelerometers) + custom cable
  • Optional: 3D printed parts (vibrant colours)
  • Powerful servo: Metal gears (you will need an arm to fight and raise your B-robot…)
  • 6x AA Battery case with ON/OFF Switch  (batteries not included)
  • Bolts+nuts needed to set everything up
  • Pair of nylon bumpers (14×5 cms)
  • Double side tape, googly eyes…

Have questions/ comments? Refer to the B-robot EVO community!

HOW TO:

UPLOAD the ARDUINO CODE to the ARDUINO LEONARDO

(skip this step if you got the Plug & Play B-robot EVO kit version. The Arduino is already programmed)

a) Install the Arduino IDE on your PC from (skip this step if you have the Arduino IDE already installed)
This B-robot code has been tested and developed on IDE version 1.6.5 and later versions. If you have a problem compiling the code, let us know
b) Download all the arduino files from GITHUB (https://github.com/jjrobots/B-ROBOT_EVO2/tree/master/Arduino/BROBOT_EVO2) or from here
Copy the files inside the BROBOT_EVO2 folder in your hard drive
c) Compile and send the code to the Arduino Leonardo
  1. Open your Arduino IDE
  2. Open the main code in /BROBOT_EVO2/BROBOT_EVO2-XX.ino
  3. Connect your Leonardo board with the USB to the PC
  4. Note: If this is the first time you connect a Leonardo board to your PC maybe you might need to install the driver.
  5. Select the board Leonardo (tools->board)
  6. Select the serial port that appears on the tools->Serial port
Send the code to the board (UPLOAD button: Arrow pointing to the RIGHT)
upload
d) Done!

CONTROL YOUR B-ROBOT EVO 2:

Android users:

We have developed a FREE APP to control the Brobot (and future JJrobots) for your Android based Smartphone/Tablet:

logo GOOGLE PLAY v2
Download it for FREE

It works sending UDP packets to the B-robot. It uses a simple layout with Throttle and Steering slicers and several buttons.

Steps to follow:

  1. Install the JJRobots control APP
  2. After turning the Brobot EVO ON, connect your smartphone/tablet to the B-robot EVO´s wifi network (remember, the WIFI´s password is 87654321)
  3. Launch the JJrobots control APP and play with your B-robot EVO!

Above: Screen capture of the JJrobots B-robot control APP (available for free in GOOGLE PLAY)

iOS users. App Store App or TouchOSC :

iOS  B-robot control APP (thanks to Xuyen for this great contribution!)ios tiny2

It is quite straightforward to use. Just connect your iPhone/iPad to the B-robot EVO´s wifi (use the password “87654321“) and launch the App.

(thanks to Xuyen for this great contribution!)

iOS TouchOSC APP: Alternative way to control the B-robot EVO. Setup guide and files here 

USEFUL LINKS:

Arduino CODE (latest version V.2.0) and the GITHUB REPOSITORY

3D PARTS (STL) Files

B-robot Challenges (robotics, Academy)

B-robot alternative frames: Stealth versionCompact version (credits to s199)

B-robot EVO 2: 3D MODEL

TROUBLESHOOTING:

My B-robot is not responding to the command sent from my smartphone/tablet

Check you are connected to the JJROBOTS_XX netwrok using the correct password (by default: 87654321) and your device has not blocked the data traffic to the B-robot (stay always connected to the robot)

The IMU gets loose/ the i2C cable is too short

The gyroscope (IMU) is one of the most important element in this robot. It provides the current angle of the robot updating its value hundred times per second. The protocol used to send the data is quite sensitive to any electromagnetic interference so a very short cable is needed to connect the IMU and the Brain Shield. At the same time, vibrations create false angle measurements so we have to isolate the Brobot´s main frame vibrations from the IMU: that is the reason to use a double sided sticky pad to fix the IMU to the Brain Shield.

Place the IMU as indicated above: Close to the Brain Shield´s i2C connector. Bend the cable if needed. If you place the IMU as above, there should not be any lateral force pushing the IMU out of place

My B-robot lacks of power or fall without reason

Adjust the current delivered by the stepper motors drivers. Use a screwdriver and gently rotate the screws indicated on the photo below. Rotating 10º-30º is more than enough.

Clockwise rotation: increase the power delivered to the motors

 

A4988 STEPPER MOTOR DRIVERS output current potentiometer

My B-robot can not stand up by itself.

If everything is ok, the B-robot only needs a little bit of help from the servo to stand up by itself. Take a look to the video below. If your robot does not behave like in the video, adjust the stepper motor drivers output power (instructions above). Keep in mind that the bumpers have two functions here: protect the electronics+robot and help it to stand up easily.

Video Player

DEBUG MODE

There is a DEBUG MODE inside the B-robot CODE. This MODE will allow you the debug the behaviour of the robot if you are having issues.  Please, refer to the B-robot community if you have problems or questions.

Look at the sketch line “#define DEBUG 0″ and change the 0 to 1…8 depending on what info you want to get. Take a look to the CODE below:

#if DEBUG==8
Serial.print(throttle);
Serial.print(” “);
Serial.print(steering);
Serial.print(” “);
Serial.println(mode);
#endif

//angle_adjusted_radians = angle_adjusted*GRAD2RAD;

#if DEBUG==1
Serial.println(angle_adjusted);

#endif

//Serial.print(“\t”);
mpu.resetFIFO(); // We always reset FIFO

// We calculate the estimated robot speed:
// Estimated_Speed = angular_velocity_of_stepper_motors(combined) – angular_velocity_of_robot(angle measured by IMU)
actual_robot_speed_Old = actual_robot_speed;
actual_robot_speed = (speed_M1 + speed_M2)/2; // Positive: forward

int16_t angular_velocity = (angle_adjusted-angle_adjusted_Old)*90.0; // 90 is an empirical extracted factor to adjust for real units
int16_t estimated_speed = -actual_robot_speed_Old – angular_velocity; // We use robot_speed(t-1) or (t-2) to compensate the delay
estimated_speed_filtered = estimated_speed_filtered*0.95 + (float)estimated_speed*0.05;

#if DEBUG==2
Serial.print(” “);
Serial.println(estimated_speed_filtered);
#endif

// SPEED CONTROL: This is a PI controller.
// input:user throttle, variable: estimated robot speed, output: target robot angle to get the desired speed
//target_angle = (target_angle + speedPControl(estimated_speed_filtered,throttle,Kp_thr))/2.0; // Some filtering : Average with previous output
//target_angle = target_angle*0.3 + speedPIControl(dt,estimated_speed_filtered,throttle,Kp_thr,Ki_thr)*0.7; // Some filtering
target_angle = speedPIControl(dt,estimated_speed_filtered,throttle,Kp_thr,Ki_thr);
target_angle = constrain(target_angle,-max_target_angle,max_target_angle); // limited output

#if DEBUG==3
Serial.print(” “);
Serial.println(estimated_speed_filtered);
Serial.print(” “);
Serial.println(target_angle);
#endif

#if DEBUG==10
Serial.print(angle_adjusted);
Serial.print(” “);
Serial.println(debugVariable);
#endif

#if DEBUG==6 //BATTERY STATUS
Serial.print(“B”);
Serial.println(battery);
Serial.print(” “);
#endif
#if DEBUG==7
Serial.print(distance_sensor);
Serial.print(” A”);
Serial.println(autonomous_mode_status);

 

USEFUL INFO: ARDUINO LEONARDO, IMU 6050 & STEPPER MOTOR DRIVER(A4988):

Arduino Leonardo:

  • Schematic can be found here
  • Info about this Arduino model here

MPU-6050 (gyro+accelerometers)

  • MPU-6050 series info can be found here
  • How to integrate it with any Arduino, here
  • Schematic and connection info, here

Stepper motor driver A4988:

 

FAQ (frequently asked questions):

Why are you using Stepper motors?

There are several options for motors: DC, Brushless, Steppers… We choose stepper motors because they have enough torque, you could connect the wheels directly without gears that generate some backslash (this is a common problem in balancing robots), they have good bearings and you will be able to control the speed of the motors with accuracy. In standard sizes these motors are cheap (we use the same motors used on a regular 3D printers) and the drivers are cheap and easy to interface with Arduino too.

Why you use a Wifi connection?

Using a Wifi connection allow us to work with a lot of devices (Smartphones, Tablets, PCs…) Bluetooth devices are cheaper but their range is usually shorter. Old devices are not supported and you could not connect it to Internet easily. The Wifi module that we recommend, allow us to create an Access Point, so you don’t need to use an existing Wifi infrastructure (cheap Wifi modules don´t let you do this). You can connect your device directly to the Robot anywhere but if you prefer you can hack it and use your own infrastructure therefore controlling your robot (or whatever you have created) over the Internet from any remote place in the world! (Cool, isn´t it?)

Why BROBOT?

Self balancing robots are fun to see and play. A self balancing robot requires sensors and control algorithms. You will find all the HOWTO and technical documents which explains the “behind the scenes” in JJROBOTS. Learn electronics and robotics creating your own BROBOT from scratch!.

There are some commercial solutions to the balancing robot, but here we want to share knowledge and thoughts. You can use the BROBOT parts to create more robots or gadgets, keep in mind all the devices used in a BROBOT are standard devices/electronics with a lot of potential. In the JJROBOTS community we want to show you how! You are now buying a self balancing robot, your are buying your own electronic and ancillary devices!

Thinking about creating a GPS self guidance robot? a modified version of BROBOT is your robot!

How much payload could carry BROBOT?

BROBOT could easily carry your soft-drink cans. We have tested with 500g of payload with success. More weight makes the robot more unstable but this could be fun also, isn’t it?

Why use stepper motors for a balancing robot?

There are several options for motors, DC, Brushless, Steppers… We choose stepper motors because they have enough torque, you could connect the wheels directly without gears that generate some backslash, they have good bearings and you could control the speed of the motors very precisely. Also they are cheap and the drivers too…

Could I use rechargeable batteries of Lipo batteries?

Yes, you could use standard AA batteries (alkaline recommended), AA rechargeable batteries (e.g. NiMh) or you could optionally use a 3S Lipo battery. Run Lipo batteries at your own responsibility.

What is the runtime of BROBOT?

With rechargeable AA batteries (e.g. Ni-Mh 2100mAh) you could expect around half to an hour of runtime

Could BROBOT work without the wifi module?

Yes, BROBOT could work and keep its stability. But, of course you could not control it without the module.

 

Could I change the name of the Wifi network that BROBOT generate?

Yes, on the configuration sketch you could change the name and also some other internet configurations. You could also connect BROBOT with your existing Wifi network

Is this a project for an Arduino beginner?

Well, BROBOT is not an easy “beginner project”, but it has a lot of documentation so you have a platform to grow your skills. You could first mount your BROBOT following the instructions and it should work OK, then you could start understanding some parts of the code and finally writing your own pieces of code…

For example it could be easily (there are tutorials for this) to write your code so the robot automatically move the arm and spin itself if you don’t send a command in 10 seconds…

More advanced hacks: Convert to a totally autonomous robot with obstacle avoiding adding a SONAR, convert to a follow line robot, and so on…

Why BROBOT electronics are not so cheap?

We are a really small startup (2 persons in our free time) and now we could only run small batch of electronics. As yo know the price of electronics drops quickly in high volume productions but we are starting… If we sell many boards and we could run more volume productions we will drop the prices!!. JJROBOTS didn´t born to get money, our spirit is to sell “good products” to found our next projects and spread the robotics knowledge

Have fun!

LINK: B-robot EVO original assembly guide 

Creating a Remotely Controlled Arduino Self Balancing Robot: B-robot EVO

How does it work?

B-ROBOT EVO is a remotely controlled self balancing arduino robot created with 3D printed parts. With only two wheels, B-ROBOT is able to maintain its balance all the time by using his internal sensors and driving the motors. You can control your Robot, making him move or spin, by sending commands via a Smartphone, Tablet or PC while it maintains its balance.

This self balancing robot reads his inertial sensors (accelerometers and gyroscopes integrated on the MPU6000 chip) 200 times per second. He calculates his attitude (angle with respect to the horizon) and compares this angle with the target angle (0º if he wants to maintain balance without moving, or a positive or negative angle if he wants to move forward or backwards). Using the difference between the target angle (let’s say 0º) and actual angle (let’s say 3º) he drives a Control System to send the right commands to the motors to maintain his balance. The commands to the motors are accelerations. For example if the robot is tilted forward (angle of robot is 3º) then he sends a command to the motors to accelerate forward until this angle is reduced to zero to preserve the balance.

Step 1: A Bit More in Depth…

The physical problem that B-ROBOT solves is called the Inverted Pendulum. This is the same mechanism you need to balance an umbrella above your hand. The pivot point is under the center of mass of the object. More information on Inverted Pendulum here. The mathematical solution to the problem is not easy but we don’t need to understand it in order to solve our robot´s balance issue. What we need to know is how should do to restore the robot´s balance so we can implement a Control Algorithm to resolve the problem.

Control System is very useful in Robotics (an Industrial automation). Basically it´s a code that receives information from sensors and target commands as inputs and creates, in consequence, output signals to drive the Robot actuators (the motors in our example) in order to regulate the system. We are using a PID controller (Proportional + Derivative + Integral). This type of control has 3 constants to adjust kP,kD,kI. From Wikipedia: “A PID controller calculates an ‘error’ value as the difference between a measured [Input] and a desired setpoint. The controller attempts to minimize the error by adjusting [an Output].” So, you tell the PID what to measure (the “Input”),where you want that measurement to be (the “Setpoint”,) and the variable you wish to adjust to make that happen (the “Output”.)

The PID then adjusts the output trying to make the input equal the setpoint. For reference, a water tank we want to fill up to a level, the Input, Setpoint, and Output would be the level according to the water level sensor, the desired water level and the water pumped into the tank. kP is the Proportional part and is the main part of the control, this part is proportional to the error. kD is the Derivative part and is applied to the derivative of the error. This part depends on the dynamics of the system (depends on the robot,´s weight motors, inertias…). The last one, kI is applied to the integral of the error and is used to reduce steady errors, it is like a trim on the final output (think in the trim buttons on an RC car steering wheel to make the car go totally straight, kI removes the offset between the target required and the actual value).

On B-ROBOT the steering command from the user is added to the motors output (one motor with a positive sign and the other with a negative sign). For example if the user sends the steering command 6 to turn to the right (from -10 to 10) we need to add 6 to the left motor value and subtract 6 from the right motor. If the robot is not moving forward or backwards, the result of the steering command is a spin of the robot

Step 2: What About the Remote Control?

We wanted B-ROBOT to be controlled by the user from almost any existing device, but we don´t want to develop a lot of different interfaces for different systems (Android, IOS, PC-windows…). Moreover, we decided to use existing (and powerful) protocols to control “things” and we found (some years ago) a protocol called OSC(Open Sound Control, more info here) used to control musical instruments like synthesizers. Very visual and powerful (we can display volume control, equalizers, lights…and create our own). To remotely control B-robot, we use OSC protocol over an Internet connection (Wifi module) using UDP packets. This is a lightweight and efficient way to send commands to our Robots!. We could also personalize the Interface we are using in our device so we will be able to control anything! (well…almost) What we need to do is to implement a lightweight library for Arduino in order to support this protocol (easy). We only use a subset of the OSC protocol to keep things small.

More info in the jjrobots webpage

Step 3: FIRST! Check You Have Everything You Need

  1. B-ROBOT electronic brain shield (or create your own PCB board using the info available here)
  2. B-Robot 3D printed plastic parts (STL models available here)
  3. Arduino LEONARDO
  4. 2x Stepper motor DRIVER (A4988)
  5. IMU MPU-6050 (gyro+accelerometer)
  6. 2x NEMA 17 stepper motors (40mm length, example:42BYGHW609)
  7. 8xAA battery holder (for NiMh or alkaline batteries)
  8. OPTIONAL: Mini servo (21g) to move the arm (this is a fun feature)

The easy way to get everything is buying from us (and that encourages us to keep doing these robots) here (plus bolts, nuts, strap…)

HINT:

We are working on other robots that are using the same electronics and ancillary elements. If you get the items above you will be capable of assemble new different robots soon. Take a look to them at the last step

Step 4: ​Programming the ARDUINO LEONARDO

a) Install the Arduino IDE on your PC from (skip this step if you have arduino already installed)

This B-robot code has been tested and developed on IDE version 1.6.5

b) Install the libraries (https://github.com/jjrobots/B-ROBOT/tree/master/libraries) Copy the folders inside the /libraries into the Arduino/libraries folder on your hard drive

JJROBOTS_BROBOT

JJROBOTS_OSC

I2Cdev

MPU6050

c)  Get the main CODE (https://github.com/jjrobots/B-ROBOT/tree/master/BROBOT).

d) Compile and send the code to the Arduino Leonardo:

  1. Open your Arduino IDE
  2. Open the main code in /BROBOT/BROBOT.ino
  3. Connect your Leonardo board with the USB to the PC
  4. Note: If this is the first time you connect a Leonardo board to your PC maybe you will need to install the driver.
  5. Select the board Leonardo (tools->board)
  6. Select the serial port that appears on the tools->Serial port
  7. Send the code to the board

Step 5: Assemble the B-robot Frame+ Ancillary Elements

Step 6: (Optional But Recommended) Controlling the B-robot Using WIFI

Setting up the TouchOSC software: If you are going to use the Touch OSC software to control the B-robot (and according to the current B-robot´s CODE available for the Arduino Leonardo), you will need to set these parameters in the TouchOSC like is shown in the images above.

Download the B-robot control layout (you can modify it if you want to) and install it using the OSCtouch APP

LINK: OSC layout used to control B-robot

Once the B.robot is switched on, a new WIFI signal will appear: “JJROBOTS-XX”. You will need to connect the controlling device to this network using the default WIFI password: 87654321

An OSC control software alternative: OSCillation and how to use it (Thanks Patrick!)

Step 7: ​Powering Up the B-robot:

  1. Lay down the B-robot on a static horizontal position in order to let it calibrate itself after powering it up.
  2. Turn the B-robot ON
  3. Let the B-robot 10 seconds to calibrate itself. Once self-calibrated, B-robot will spin its wheels a little.
  4. Time to stand up!: Use its arm or help it to stand up.

HINT: If the stepper motors do not have enough power to spin the wheels, try to adjust the current output in the A4988 stepper motor drivers rotating the screw indicated in the photo

QUESTIONS?

have a look to the B-robot forum

Step 8:

Other robots created (or under the last stage of development) which use the same electronics and ancillary elements.

PANDORA Junior DXs – 3D Design Concept

DIY 3D Printer – PANDORA Junior DXs (Design eXtreme single)

3D Design Tool: SketchUp Pro

Technical Specifications

Printing

Technology: FFF(Fused Filament Fabrication) / CoreXY
Build Volume: 223 (W) x 207 (D) x 250 (H) mm – Heatbed
Layer Resolution: 50 ~ 200 microns
Filament: ABS or PLA, Nyron, HIPS, PVA… 1.75 mm diameter
Nozzle Diameter: 0.4 mm (0.2mm, 0.3mm, 0.8mm)
Print File Type: .Code, .STL
Layer Resolutions:

  • Fast: 200 micron (0.2 mm)
  • Normal: 100 micron (0.1 mm)
  • hHigh: 0.06 micron (0.06 mm)
  • Ultra High: 0,04 micron (0.04 mm)

Size and Weight

Product Dimensions: 410 (W) x 410 (D) x 485 (H) mm
Product Weight: 11 kg(?)

Software

Software Bundle: Cura, Slic3r, KISSlicer / Octoprint, Printrun, Repetier-Host, MatterControl
Supported File Types: .STL, .OBJ, .AMF, .Gcode
Operating Systems: All (Web-based): Windows, Mac OS, Linux

Firmware

Arduino: Modified Marlin v1.0.2-2
Raspberry Pi: Rasbian, Octoprint, SSH, Samba, VNC, WiringPi

Hardware

Base Plate: Profile DRF 2020, Acrylic
Step Motor: NEMA 17 – Phase: 4, Step Angle: 1.8 Deg/Step, Holding Torque: 2.6Kg.cm

  • X/Y/Z/E – 4EA
    Cartesian (xyz): X/Y Head: Profile DRF 2020, Z Bed: 10mm Linear Shaft and 8D Screw Rod

Electrical

Control Board: Arduino Mega 2560
Control Shield: Ramps 1.4 Board
Display Board: Reprap Discount Smart Controller LCD 2004
Raspberry Pi: Raspberry Pi 2/3
Camera: Raspberry Camera
Power Requirements: AC 100 – 240 V, 1.4 Amps, 50-60 Hz, 220 W
Connectivity: USB, SD Card, Wi-Fi (Web-based)
Temperature:

  • Nozzle temperature: 170 – 270
  • Heated bed temperature: 50 – 100
  • Operational temperature: 10 – 40
  • Storage temperature: 0 – 32

https://youtu.be/MC2KeKuKM1A


Thanks for watching!……..Coming soon!……..Updating……

Blog:
http://zddh.blogspot.kr/2017/12/pandora-junior-dxs-3d-design-concept.html

The open source PANDORA DXs hardware and software is free and made with love. Please show your level of support with a voluntary donation.

Donate:
https://www.paypal.com/cgi-bin/webscr?cmd=_s-xclick&hosted_button_id=RDN7ZGAVFS5UE

DIY Delta 3D Printer – HexaBot

DIY Delta 3D Printer – HexaBot
3D Design Tool: SketchUp Pro


Technical Specifications


Printing


Technology: FFF(Fused Filament Fabrication) / Delta
Build Volume: 95 (W) x 95 (D) x 135 (H) mm

  • Auto running Heatbed
    Layer Resolution: 50-200 microns
    Filament: ABS or PLA, Nyron, HIPS, PVA… 1.75 mm diameter
    Nozzle Diameter: 0.4 mm (0.2mm, 0.3mm, 0.8mm)
    Print File Type: .Gcode, .STL
    Layer Resolutions:
  • Fast: 200 micron (0.2 mm)
  • Normal: 100 micron (0.1 mm)
  • hHigh: 0.06 micron (0.06 mm)
  • Ultra High: 0,04 micron (0.04 mm)

    Size and Weight


    Product Dimensions: 260 (W) x 300 (D) x 460 (H) mm
    Product Weight: 4.5 kg


    Software

Software Bundle: Cura, Slic3r, KISSlicer / Octoprint, Printrun, Repetier-Host, MatterControl
Supported File Types: .STL, .OBJ, .AMF, .Gcode
Operating Systems: All (Web-based): Windows, Mac OS, Linux


Firmware


Arduino: Modified Marlin v1.0.0
Raspberry Pi: Rasbian, Octoprint, SSH, Samba, VNC, WiringPi


Hardware


Base Plate: Profile DRF 2020, Acrylic
Step Motor: NEMA 17 – Phase: 4, Step Angle: 1.8 Deg/Step, Holding Torque: 2.6Kg.cm

  • X/Y/Z/E – 4EA
    Cartesian (xyz): X/Y Head: LM Guide, Z Bed: 10mm Linear Shaft and 8D Screw Rod


    Electrical


    Control Board: Arduino Mega 2560
    Control Shield: Ramps 1.4 Board
    Display Board: Reprap Discount Smart Controller LCD 2004
    Raspberry Pi: Raspberry Pi B
    Power Requirements: AC 100 – 240 V, 50-60 Hz, 12 VDC, 4.5A, 54 W
    Connectivity: USB, SD Card, Wi-Fi (Web-based)
    Temperature:

  • Nozzle temperature: 170 – 270
  • Heated bed temperature: 50 – 100
  • Operational temperature: 10 – 40
  • Storage temperature: 0 – 32

    https://www.thingiverse.com/thing:917729


    Thanks for watching!…….coming soon!……Updating……

The open source HexaBot hardware and software is free and made with love. Please show your level of support with a voluntary donation.

Donate:
https://www.paypal.com/cgi-bin/webscr?cmd=_s-xclick&hosted_button_id=RDN7ZGAVFS5UE

MobBob V2 Remix Upgrade – Smart Phone Controlled Robot

[Update 20160212]
Add MobBob2_Remix_PowerBank_Hook.stl
Add MobBob2_Remix_Jacket.stl
Add MobBob2_Remix_Nano_Shield_Mount.stl

[Update 20160120]
Add Test #3 Video

[Update 20160119]
Add Test #1, #2 Video
Add MobBob2_Remix_Hand_Back_L.stl, MobBob2_Remix_Hand_Front_L.stl
Add MobBob2_Remix_Arm_Back_L.stl, MobBob2_Remix_Arm_Front_L.stl
Add MobBob2_Remix_Shoulder_L.stl
Add MobBob2_Remix_Hand_Back_R.stl, MobBob2_Remix_Hand_Front_R.stl
Add MobBob2_Remix_Arm_Back_R.stl, MobBob2_Remix_Arm_Front_R.stl
Add MobBob2_Remix_Shoulder_R.stl

[Update 20160105]
Printing errors corrected
MobBob2_Remix_Foot_L_Top.stl, MobBob2_Remix_Foot_R_Top.stl

[Upgrade 20160104]
Redesign Foot
MobBob2_Remix_Foot_L_Top.stl, MobBob2_Remix_Foot_L_Floor.stl
MobBob2_Remix_Foot_R_Top.stl, MobBob2_Remix_Foot_R_Floor.stl
Base Design: http://www.thingiverse.com/thing:1232619


Smart Phone Controlled Robot – MobBob V2 Remix Upgrade


3D Design Tool: SketchUp Pro
Design concept: RAPIRO – The Humanoid Robot and Gundam

This is an upgrade version of my MobBob V2 Remix robot.

MobBob is a smart phone controlled robot. By harnessing the power of your smart phone, MobBob is a walking, talking robot with voice recognition and computer vision that you can build for around $35. I will be continuing to extend his features over time. I want MobBob to be a companion robot that everyone can afford and have fun with.

You can see videos of MobBob V2 Remix upgrade in action here:
https://youtu.be/8nO0kziJvsk – 3D Design
https://youtu.be/ehrsIDJcVZY – Test #1
https://youtu.be/j0oz8OPYhNs – Test #2
https://youtu.be/5z4Ps11t-vE – Test #3
…..
Coming soon!!

The main aims of the V2 remix were to:

Support standard 9g servos [previously I was using Tower Pro SG90 servos]
Make everything easier to assemble [no more need for glue]
Make it easier to adapt/modify for other phones. The new bracket system made it easier to exchange a new phone / the battery holder.

Also, in my V2 Remix Upgrade build, I’m also using the Arduino Nano instead of the DIY Nano shield, so the entire build is smaller and tidier. 🙂

MobBob V2 Remix Upgrade uses the same software as the original RAPIRO.

You can find the latest Arduino code here: https://github.com/Ishiwatari/RAPIRO
The modified code is included: http://www.thingiverse.com/thing:1235865

You can download the latest version of the Android from Google Play – it is free, ad-free, and without IAP:
https://play.google.com/store/apps/details?id=com.github.luzhuomi.rapicommand

You can find more detailed build and wiring instructions here:
…coming soon…

The parts that you need to print:

1 x Leg Left
1 x Leg Right
1 x Foot Left Floor
1 x Foot Right Floor
1 x Foot Left Top
1 x Foot Right Top
1 x Waist
1 x Arduino Nano Holder
1 x Phone Mount Base
2 x Phone Mount Side
1 x Phone Mount Gear
1 x Phone Mount Back Plate
1 x Phone Mount Conn
2 x Phone Mount Bolt
2 x Phone Mount Nut
1 x Battery Bank Rack [18650 x 2] or Power Bank
1 x Battery Mount Cover or PowerBank Hook
1 x Jacket
1 x Cap
1 x Hand Back Left
1 x Hand Front Left
1 x Arm Back Left
1 x Arm Front Left
1 x Shoulder Left
1 x Hand Back Right
1 x Hand Front Right
1 x Arm Back Right
1 x Arm Front Right
1 x Shoulder Right

The non-3D printed parts you need are:

6 x Tower Pro SG90 servos [for Shoulders, Arms and Hands]
4 x EMAX ES08MA II Mini Metal Gear Analog Servo [Strengthening the power of the Legs and Foots]
1 x Arduino Nano ATmega328 [see note below]
1 x HM-10 BLE Bluetooth 4.0 CC2540 CC2541 Serial Wireless Module [or HC-05]
1 x 5V Micro USB 1A Lithium Battery Charging Board [see note below]
1 x DC-DC Converter Step Up Boost Module 2-5V to 5V 1.2A
1 x Rectangle On/Off Long Rocker Switch SPST
2 x Snap-In Single ‘A’-‘AA’ Battery Contacts 209 [KEYSTONE ELECTRONICS CORP.]
2 x Snap-In Single ‘A’-‘AA’ Battery Contacts 228 [KEYSTONE ELECTRONICS CORP.]
2 x 18650 Lithium ion Batteries
1 x 300mm USB 2.0 A Male to Micro USB B 5pin + Mini B Male Y Splitter Cable
1 x Smart Phone [see note below]
4 x M3 5mm [for Foot Cover]
2 x M2 10mm [for Phone Connect]
4 x M2 5mm [for Phone Mount Back Plate]
2 x 2mm 5mm Tapping screw [for Foot servos]
2 x 2mm 8mm Tapping screw [for Hip servos]
2 x 1mm 5mm Tapping screw [for Foot servos hone]
2 x 1mm 8mm Tapping screw [for Hip servos hone and Shoulder]
2 x M3 15mm [for Jacket]
2 x M3 Nut [for Jacket]
4 x 2mm 15mm Tapping screw [for Jacket]
12 x M2 15mm [for Arm and Hand]
[Note: I got the servos, Arduino Nano, Bluetooth Module and Battery for under $30.]

Arduino Nano:

This is a small, Arduino compatible ATmega328 board with DIY extension board. MobBob V2 app connects to the Bluetooth module using its Bluetooth LE service. The app to support other Bluetooth cards.

Battery Extender:

You can use other batteries that provide 5V with a steady current. If you use other batteries, you may need to adapt the battery rack for your battery’s size.
Use 18650 Lithium Battery Charging Board With Protection Charger Module and Step Up Boost Module 3.7V to 5V for Smart Phone
http://www.thingiverse.com/thing:1235749

Smart Phone:

You can use other Android Smart Phones with This app.
You do not need to adapt the size of the phone holder for your phone. The app has been successfully tested with Nexus and Samsung, LG phones, but should work on other Android phones.

Instructions:

Print all the required parts
Get all the non-3D printed parts
Assemble as per the photos – I’ll be writing some more detailed instructions on my website soon!
Install the Arduino code from the GitHub link in the description – You will need to update the Arduino pins in the code to match yours, and probably update the centering values for the servos.
Install the Android app from the link in the description.

Have fun!

If you hit any problems, please post a question on this website: [http://www.rapiro.com], here, or on YouTube channel. A few people have built RAPIRO now, so there are people around who can help.

Coming soon update!!

The open source Mobbob V2 software and hardware is free and made with love. Please show your level of support with a voluntary donation.

Donate:
https://www.paypal.com/cgi-bin/webscr?cmd=_s-xclick&hosted_button_id=RDN7ZGAVFS5UE

Post-Printing

How I Designed This

Design Tool

Google SketchUp Pro 8

Print Settints

Printer Model: PANDORA DXs – DIY 3D Pronter
Slicer: Cura 15.04.2


Layer height (mm): 0.1
Shell thickness (mm): 0.8

Bottom/Top thickness (mm): 1.2
Fill Density (%): 00

Print speed (mm/s): 50
Print temperature: 200
Bed temperature: 70

Support type:

  • Touching buildplate:
    MobBob2_Remix_Phone_Mount_Side.stl,
    MobBob2_Remix_Phone_Mount_Nut_L.stl, MobBob2_Remix_Phone_Mount_Nut_R.stl,
    MobBob2_Remix_Phone_Mount_Conn.stl,
    18650_Battery_Bank_2x_Cover_swC_r01.stl
  • Everywhere:
    MobBob2_Remix_Nano_Shield_Holder.stl,
    MobBob2_Remix_Battery_Mount_Cover.stl,
    MobBob2_Remix_Jacket.stl,
    MobBob2_Remix_Hand_Back_L.stl, MobBob2_Remix_Hand_Front_L.stl,
    MobBob2_Remix_Arm_Back_L.stl, MobBob2_Remix_Arm_Front_L.stl,
    MobBob2_Remix_Shoulder_L.stl,
    MobBob2_Remix_Hand_Back_R.stl, MobBob2_Remix_Hand_Front_R.stl,
    MobBob2_Remix_Arm_Back_R.stl, MobBob2_Remix_Arm_Front_R.stl,
    MobBob2_Remix_Shoulder_R.stl

Platform adhesion type: Brim

Filament: PLA
Filament Diameter (mm): 1.75


3D Files:

https://www.thingiverse.com/thing:1235865

Custom Section

Source code

by ShotaIshiwatari is licensed under the Creative Commons – Public Domain Dedication license.
modified by Zalophus

on the command line, enter:
// #M1 – robot will move forward
// #M2 – robot will move backward
// #M3 – robot will turn right
// #M4 – robot will turn left
// #M5 – robot will raise his hand and wave the left hand. LED will become green and flashing
// #M6 – robot will lower his left hand. LED will become Yellow
// #M7 – robot will move both arm and contract his hands. LED will become Blue
// #M8 – robot will wave goodbye with his left arm. LED will become RED.
// #M9 – robot will raise its right arm and move its waist. LED will become BLUE
// #M0 – robot will go to initial position

CAPS LOCK is important when you input a command via the serial monitor..
Reading through the source code.
Each movement of the preset (# M1 ~ # M9), consists of pattern of 8 frames.
Each frame is defined values ​​uint8_t type sixteen (motion).
This can be changed modifying the number of frame per pattern.MAXFN
Lets take #M0 for example:

uint8_t motion[MAXMN][MAXFN][16]={
{ // 0 Stop
{ 90, 90, 0,130, 90,180, 50, 90, 90, 90, 90, 90, 0, 0,255, 10},
{ 90, 90, 0,130, 90,180, 50, 90, 90, 90, 90, 90, 0, 0, 0, 0},
{ 90, 90, 0,130, 90,180, 50, 90, 90, 90, 90, 90, 0, 0, 0, 0},
{ 90, 90, 0,130, 90,180, 50, 90, 90, 90, 90, 90, 0, 0, 0, 0},
{ 90, 90, 0,130, 90,180, 50, 90, 90, 90, 90, 90, 0, 0, 0, 0},
{ 90, 90, 0,130, 90,180, 50, 90, 90, 90, 90, 90, 0, 0, 0, 0},
{ 90, 90, 0,130, 90,180, 50, 90, 90, 90, 90, 90, 0, 0, 0, 0},
{ 90, 90, 0,130, 90,180, 50, 90, 90, 90, 90, 90, 0, 0, 0, 0}
},

I put numbers so you can visualy make sense of what a pattern is, and what a frame contain.
Movements consist of pattern. Pattern are made of frames. Each frame contrain the rotation angle of every servo, the values of the RGB LED and a Time to perform the action.

Head horizontal rotation angle (Head yaw) (left) 180 <—> 0 (right)
Hip horizontal rotation angle (Waist yaw) (left) 180 <—> 0 (right)
Right shoulder up and down angle (R Shoulder yaw) (bottom) 0 <—> 180 (above)
Open right shoulder angle (R Shoulder pitch) (closed) 90 <—> 180 (open)
Right hand opening and closing angle (R Hand grip) (closed) 50 <—> 110 (open)
Left shoulder up and down angle (L Shoulder yaw) (bottom) 180 <—> 0 (top)
Open left shoulder angle (L Shoulder pitch) (closed) 90 <-> 0 (open)
Left hand opening and closing angle (L Hand grip) (closed) 130 <—> 70 (open)
Right foot horizontal rotation angle (R Foot yaw) (left) 0 <—> 180 (right)
Twist angle of the right foot ankle (R Foot pitch) () 0 <—> 180 (outside)
Left foot horizontal rotation angle (L Foot yaw) (left) 0 <—> 180 (right)
Twist angle of the left foot ankle (R Foot pitch) (within) 180 <—> 0 (outside)
Red component of the eye (R) 0 <—> 255
Green component of the eye (G) 0 <—> 255
Blue component of the eye (B) 0 <—> 255

Here are some other helpful commands that can be used to control the LED and each servos individually.

LED CODE sample

// #PR000G255B000T010 – MAX GREEN COLOR
R,G,B values between 0 and 255
T is the time component to get to desired color

LIMBS MOVEMENT
Sxx refers to one of the 12 motors (from S00 to S11),
A000 up to A180 is the angle where to servo incline,
Txxx is the time to perform the movement.
you can combine two commands, i tried more but it didn’t work..

// #PS00A000T010#PS00A180T010 – full head movement from side to side
// #PS01A000T010#PS01A180T010 – Waist
// #PS02A000T010#PS02A180T010 – r Shoulder
// #PS03A050T010#PS03A180T010 – r Arm
// #PS04A030T010#PS04A140T010 – r HAND
// #PS05A000T010#PS05A180T010 – l Shoulder
// #PS06A130T010#PS06A010T010 – l Arm
// #PS07A030T010#PS07A180T010 – l hand
// #PS08A000T010#PS08A180T010 – r Foot yaw
// #PS09A000T010#PS09A180T010 – r Foot pitch
// #PS10A000T010#PS10A180T010 – l Foot yaw
// #PS11A000T010#PS11A180T010 – l Foot pitch

// #PS00A090S01A090S02A000S03A090S04A090S05A180S06A090S07A090S08A090S09A090S10A090S11A090R000G000B000T005

Polargraph Drawing Machine

This machine, a variation on the hanging-pen plotter is a conspicuous and wilfully naive attempt to break out of the pristine, pixel perfect, colour-corrected space that exists inside our computers. It’s a drawing machine, that takes a pen (a human tool) and uses it to draw in a singularly robotic way, with some grand results.

It doesn’t draw at all like we would (though it could), and we would struggle to draw exactly as it does (though we could).

It can draw on things bigger than itself – the question is really “how long is a piece of string?” when it comes to working out it’s maximum area.

It’s easier to look at what it does, than to explain it, so just have a look.

Step 1: History

Well there have been lots of new drawing machines doing the rounds lately, there’s a real thirst to see devices that leap out of the virtual into the
physical. For me, it’s all too easy to produce digital things which are interesting – programming or mash-ups or virtual experiments are devalued because they are intangible, you can run a hundred, a thousand, a million variations in a day – it’s the proverbial roomful of monkeys with typewriters. The output becomes disposable, it get’s hard to see the value, the craft.

So 3D printers and other desktop manufacturing tools and technologies (laser cutters etc) have got more and more popular, it’s hard to overestimate how much hunger there is for a tangible, physical, touchable, smellable product of all this clever-clever digital work.

So this isn’t wholly original, check out this prior art for more inspiration:

Hektor – the daddy of all hanging drawing machines
Der Kritzler – the smartest one yet
AS220 Drawbot – the basis for mine
SADBot – Instructable for an automatic drawing machine on the same pattern by Dustyn Roberts

But this is the original Polargraph! The term is a portmanteau word invented for this instructable, and it has caught on. People who don’t know their drawbot history often use the word to describe any hanging-v plotter, but it is actually means something very specific: A machine that runs the Polargraph software.

Mostly based on the success of this instructable, I started a little workshop making Polargraph parts, and the next-generation Polargraph gear (PolargraphSD). Couple of links below:

Polargraph website
Polargraph wiki and code
Flickr stuff

Step 2: Parts

There’s a hundred different ways of making a machine like this, but I’m going to show you how I make mine, as a jumping off point. I hope you’ll see some places it can be improved.

Electronics.

  • Microcontroller – Arduino Uno or compatible. I’ve used a Seeeduino here. (from coolcomponents). Be aware that some “arduino compatible” boards that use FTDI chips are only really Arduino Duemilanove compatible – they have very slightly less memory, so the Polargraph code no longer fits on it.
  • Motor drivers – Adafruit’s Motoshield v1. A modern classic. It can drive two stepper motors each drawing up to 600mA and has pinouts for a servo too, so is perfect for this project. This is now discontinued by Adafruit, but boards like them are widely available on ebay (search for “L293D motor shield arduino”). Adafruit _do_ make a new motorshield that is even better, but I haven’t got one to test one.
  • Motors – Look for motors with a current rating of around 600mA (0.6A).  Mine were 400 steps per revolution (0.9 degree per step), NEMA 16 stepper motors, with a 5mm diameter shaft off ebay, but something like this NEMA-17 with a 0.4A current rating would do nicely, as would this one from Adafruit.Power supply. 1 amp (1000mA) Variable voltage AC/DC power supply. Set the voltage as high as you dare. If things start getting hot, just turn it down a bit. 9v will be fine, 12 may be pushing it, but it depends on your motors really. At peak, the machine might be drawing 1.2 amps (2x 600mA), so you might benefit from a beefier-than-average power supply. That said, it ran for months on a 600mA supply before I did something silly and it stopped. (expro.)

Gondola.

  • This is the pen holder. I am from the “heavy and stable” school of thought. I think it makes for a more definitive impression, and a cleaner line.
  • 3x 6003Z deep groove bearings. (simplybearings.co.uk)
  • 50mm length of K&S stock #144 brass tubing (21/32″, 16.66mm dia). (hobbies)
  • Laser cut acrylic parts.  The original is made of corrugated cardboard and a blank CD, just glued on, so this is by no means necessary. (Ponoko)

Running gear.

  • Beaded cord.  This is used in roller blinds.  (ebay – a shade better).  You could use metal ball chain if it matches the pitch.
  • Sprockets. Don’t seem to exist off-the-shelf, so I made these 3D printed ones (shapeways).
  • Counterweights.  I used a bolt with a stack of washers hung on it.

Hardware.

  • Surface – big flat surface to base your machine on.  Discussed in the next step.
  • Brackets – laser cut plywood to allow the motors to be fastened to a flat wall.  If you are mounting on a board, you might be able to just simply stick the motors directly on the top edge of the board. (Ponoko)

Step 3: Sprocket up!

I couldn’t find a source for these beaded cord sprockets.  Roller blind mechanisms have them in, but not in an easily usable form.  I made my own and had them printed through Shapeways.  John Abella has made a parametric sprocket suitable for other bead spacings that can be 3d printed at home if you have access to something like a makerbot or a reprap.

Push-fit a sprocket onto the 5mm shaft of the motor.

Step 4: Prepare your motors

Strip the ends of the motor wires and tin them. Unless you have very long wires already on them, you’ll be extending them, and use whatever is to hand to do it – in my case, I used plain screw terminals.  Make sure you label your extension cable too.

Step 5: The drawing surface

Find a big board or something to use as your surface.  Your board should be at least 150mm bigger on each side than the largest sheet of paper you want to draw on.

You can use a wall if you have some motor mounting brackets, but I was always terrified about it going wrong and scrawling marker pen over my wall.  My landlady would be unimpressed, I feel.

Using a board means you can tilt it slightly too just by leaning it against the wall, and that’s a good thing because the weight of the gondola presses the pen to the page.  When the surface is perfectly vertical, it’s hard to get any pressure against the page – the lines tend to come out a pretty woolly.

I went down the local DIY shed and scavenged in the offcuts bin for the biggest bit of chipboard I could fit in my little car, but I’ve also had good success with building a machine based on the biggest IKEA Ribba picture frame.  This has the added feature that you can use it as a picture frame afterwards, amazingly.  A whiteboard is a good alternative too, because you can test quickly, but any kind of flat surface will do.  My first one was only big enough for A3, and worked fine, so don’t feel it has to be massive.

Step 6: Mount your motors – edge style

Your motors should be mounted so that the sprockets are as close as possible to the drawing surface.  If you have a thick surface, you can get away with just sticking your motors to the top edge of the board with double-sided foam tape.  This is actually a nice way of doing it because it cushions the vibration too.  The motors do tend to twist a bit, because their little foam rafts have some stretch in them, but on mine it wasn’t really a problem unless I left the gondola hanging for days.

This arrangement is much neater when it comes to cabling and things too.  It all hangs down the back.

If you have access to a 3d printer, there is a neat stepper motor mount available at http://softsolder.com/2011/08/23/nema-17-stepper-motor-mount/.

Step 7: Mount your motors – front style

This is way I’ve come to mount the motors, and it looks a bit untidy, but it is less dependant on the type of your drawing surface – it can be stuck onto anything basically, including walls and other enormous surfaces.

I have attached plans for a motor mount to be lasercut from 3mm thick plywood, but there’s nothing clever about it except that it only slots together, so the motory bits can be removed easily, leaving the main mount plates in place.  I have got it on a Ponoko P1 sized piece of board, and you will need two of these cut.The plans for Der Kritzler include window-mountable servo holders that use suction cups.  That bracket is probably stronger than mine too, but it needs more parts to build it.

Fasten the big plates onto your surface in the top corners.  They should be exactly level.  I use double sided sticky foam tape for more or less everything, but make sure you use plenty because they are fairly heavy, and there is some vibration.

Step 8: Electronics – Arduino

You need an Arduino UNO board, I used a Seeeduino v2.21 here – it did the job very nicely back in the day, but a couple of new features have been added to the code and so it doesn’t fit on anymore. Genuine UNOs have very slightly more space for programs.

Upload the source code to the arduino. Seriously. Actually do this. Nothing will work until you do this. Do it.

Look at this fine guide courtesy of Adafruit for help. Or anywhere on Instructables, or one of the hundreds of Arduino tutorials on the web.

Because it changes regularly, I have not attached a copy of the code itself to this step, but the very most recent version can be downloaded in a bundle from the polargraph code repository. Download the file called Polargraph.___.zip.

Unzip the bundle. Inside it is a folder called arduino-source which contains (you guessed it), the source code for the arduino part of the project.

Inside arduino-source there is a folder called libraries. It contains the libraries you need (

Adafruit’s AFMotor and Mike McCauley’s Accelstepper)

It also contains a folder called polargraph_server_a1. This is the polargraph firmware source code.

Copy the contents of arduino-source/libraries into your Arduino/libraries/folder.

Copy arduino-source/polargraph_server_a1 into your Arduino/ folder.

You should have created three new folders on your disk:

  • Arduino/polargraph_server_a1/
  • Arduino/libraries/Accelstepper/
  • Arduino/libraries/AFMotor/

Start Arduino IDE.

Go to File->Sketchbook->polargraph_server_a1

Fourteen files will open up and be displayed as tabs in the IDE. This is the source code of the firmware.

Press the “verify” button in the toolbar to try and compile it.

If it compiles, press the “upload” button in the toolbar to upload it.

Of course the source code is also available in the code repository – https://github.com/euphy/polargraph_server_a1 – should you want the very most recent version, but you’ll have to figure that one out yourself.

Once you do that, you should confirm that it is working properly – use the serial monitor on the board, set to 57600 baud to make sure that it is issuing “READY” every couple of seconds (see the last image).

Step 9: Electronics – Motorshield

The motorshield is usually supplied as a kit, it’s easy to solder up, follow the instructions on the Adafruit site. It’s brilliant. I am an Adafruit fanboy, so sue me. Not much more to say about it. Adafruit discontinued the v1 motorshield in 2013. Lots of people are still selling clones of the v1 design on ebay, just search for “L293D arduino motor shield”.

(The firmware can be compiled to use the Adafruit Motorshield v2, but it’s not as good. There are instructions in the source code that show you what you need to change.)

The motorshield has two stepper motor ports, one on either side. It takes it’s power from the host arduino, but has a separate connector that you can use to connect an external power supply. If you have a power supply that has bare leads, you can screw them in here (make sure you get the polarity right) use this and remove the power jumper from beside it. I’m going to stress that the power connector is wires up properly – +V on the left hand wire, GND on the right. There is no reverse polarity protection on this board, so if you do it wrong it’s likely you’ll damage the board, and maybe your arduino too.

If you don’t use it, you should plug your external power supply directly into your arduino, and leave the power jumper ON. I am wiring directly, because it’s better practice to have entirely separate supplies for motor and logic.

I also added little heat sinks to the driver chips (L293Ds) on the motorshield. They get hot, and you can use a fan to cool them if you have one spare, and really, I don’t know if they every really get dangerous, but with heatsinks on I feel a more comfortable letting them run for hours and hours.

Step 10: Electronics – Wiring

Each motor has two circuits, or coils in it, and a bipolar stepper has four wires coming out of it, two for each circuit. Most steppers will have a datasheet that will let you know which colour wires lead to which coil. Find out, either using your datasheet, or a multimeter (a bit more about steppers, and how to figure them out on adafruit and this article helped me figure it all out.).

Mine have the red and the blue wire attached to one coil, and the white and the yellow wire on the other coil.

The two motors should be wired up with their coloured wires matching left and right. So on the left hand side, you should have wire pair 1 (red/blue) in the top two terminals, and wire pair 2 (yellow/white) in the bottom two terminals. And on the right, it’ll be exactly the same: pair 1 in the top, pair 2 in the bottom.

I stuck my arduino to a bit of foamcore board stuck on the back of my drawing surface. Just makes it a bit easier to deal with.

Push the motorshield into the arduino, and fire it up!

Step 11: Controller software – install

The setup is ready to test! The software you use to control it is a little application written in Processing. You can run this from the source code, but it’s probably easier to use one of the pre-compiled binaries that I’ve made. The most recent code bundle has the latest versions for Mac, Windows or linux. Download the file called Polargraph.*.zip (rather than the “source code” files).

(That bundle also includes all the source for the controller, and the firmware, and all the Processing and Arduino libraries you need to run from source.)

Download it, unzip it, and run the executable in the controller folder. It’ll open up very small, but maximise the window to see more. It will automatically create a default configuration file in the same folder as it runs in, and you should then click “save properties” in the top-left corner to save the new window size as the default.

Compile from source

If you’re curious about Processing, you’re right to be: It’s ace. There are useful tutorials on processing.org, and of course here on Instructables too. It’s basically java, but optimised to run little stand alone programs with graphics. If you’re interested in keeping on the leading edge of the controller development, you might like to check out the code directly from the repository and compile it yourself. Another reason: The precompiled binaries that I distribute are a little idiosyncratic, and sometimes refuse to work on some people’s machines. If you compile from source, then it’ll work at least.

Couple of notes – The controller is getting a bit long-in-the-tooth now, and I haven’t updated it to use Processing 3 yet. So in the meantime, it will only compile in Processing 2.x. Additionally, the libraries have also since moved on since it was written, and it’ll only work with the versions in the zip file (referred to above). I’m working on an update, but it’s not ready yet.

  1. Install Processing 2.2.1 (From https://processing.org/download/?processing)
  2. Run Processing, find where your sketchbook folder is: (File->Preferences, sketchbook location).
  3. Install libaries: Unzip the code bundle, and copy the contents of the processing-source/Processing libraries into sketchbook/libraries.
  4. Install project: In the code bundle, copy the whole processing-source/polargraphcontroller folder into your sketchbook folder.
  5. Restart Processing, and open the controller with File->Sketchbook->polargraphcontroller.
  6. Run: When some files have opened up and you can see some code, hit the play button in the toolbar (or use Ctrl-R) and you should see the controller spring into live.

It’ll only be a small window, so go ahead and stretch it so you can see everything. If it worked, then well done. NEXT!

Step 12: Controller software – Primer

Ok, in the controller window there are three main elements.

  1. The control panel with all the buttons down the far-left,
  2. The grey rectangle in the middle that represents the machine itself,
  3. The command queue down the right-hand side of the machine.

Some of the controls are just to do with the controller (like load image), but some (like set home or render pixel) send commands to the machine itself. Some of the controls are number spinners, click and drag up and down on them to change their value.

Move the mouse over the machine and you’ll see some lines overlaid that represent the hanging cords. You can zoom in and out from the machine using the mouse scroll wheel, and “grab” it and move it around using the middle mouse button drag.

If a command is issued to the machine, it’s held in a queue until the machine signals to say it’s ready to do something. The command queue is shown on the far right of the app window. When you first start it up, it’s in paused mode, and is pre-loaded with a couple of default settings. You can start it and stop it by clicking on the queue header (where it says COMMAND QUEUE: Paused – click to start). The queue can be emptied with the reset queue button. While the queue is paused, individual commands can be removed from it by clicking on them.

The interface is separated into three tabs, switch between them using the labels at the very top. Each tab has a different set of buttons in it’s panel.

  1. Input. Used for loading images, moving, resizing, selecting an area to draw, as well as issuing the drawing commands. Click on load image and browse to an image, (png or jpg), then move image and resize image to place it on the page.
  2. Setup. Used for defining the machine hardware. Change the machine size, the page size and position and the home point position. Also change the motor speeds and pen size. Once you’ve changed the machine on-screen to reflect the real size of your own machine, press upload machine spec to send it to the machine.
  3. Queue. Used for exporting and importing the queue to and from a text file. They are in plain text, so it’s easy enough to hack them.

Next let’s connect it up.

Step 13: Controller software – introduce it to your hardware

To get the controller to talk to the machine, change to the setup tab and then click on the serial button. This will pop up a little window with a list of the available serial ports in it. If you know which one to try, click it. If not, just go through them, waiting for a couple of seconds between each one until you see the top line of the main window turn green and show Polargraph READY!

The hardware broadcasts that it’s ready every couple of seconds, which is why you might need to wait. If you don’t want to connect it (because you haven’t got a machine yet) just choose no serial connection.

Job done! Close the serial port window and then click save properties in the control panel, so the controller remembers it for next time.

Step 14: Controller software – make it move!

Confirm you have set the right serial port, and that it’s communicating with the arduino by looking for a Polargraph READY! at the top of the window. This line will be red if it’s not connected. If you connect the machine after starting the controller, then you’ll probably need to close and restart the controller too.

If you’re running from Processing, then you should also be seeing incoming: READY in the Processing console every couple of seconds, in the background.

That’s great! Unpause the command queue, and you’ll see the first couple of commands get gobbled up by the machine, one after another. Click Set home.You’ll see a command appear in the the command queue, and then it’ll get sent to the machine right away. You will see the big purple dot that signals the location of the pen will move to the be in the middle of the top edge of the machine on-screen. The motors themselves will also give a little wriggle, and you’ll find they’re locked – they’re now under power!

Ok, now click the Move pen to point button, which is as close to a manual move command as you have, and click somewhere right down at the bottom of the machine. With luck, you will hear and see the motors whirr into life, accelerate and then decelerate back down again.

The purple spot will move too. This is where the machine thinks the pen is.

Try this again, and make sure the sprockets are moving in the right direction. When the machine is moving the pen down the page, the left-hand motor will be spinning clockwise, and the right-hand motor will be spinning anti-clockwise. When the machine is moving up the page, it’ll be the other way around.

If one, or both of your motors are going in the wrong direction, you might have got your datasheet wrong, or made an error when labelling them up or something. You just need to swap your two pairs of wires around. To be honest, trial and error is as good a way of working out the correct circuits as anything else, but it’s hard to do until you’re absolutely sure all the rest of it is working right.

Good work! I recommend a cup of tea! There’s no part of a project quite so rewarding as that first moment when it moves, or makes a noise, or electrocutes you, I think you’ll agree.

Step 15: Assemble the gondola

The gondola is the pen holder. There’s a few alternative designs out there for them, including this 3D printable one that seems to do the business nicely. My design is much heavier, and has a hollow centre so that the pen can always be in the exact point where the cords converge. In practice, I’m unclear about how much difference this makes, but it makes me feel good.

I made the first one from corrugated cardboard, and a blank CD, stuck to some ball bearings (see the last picture on this step). Later I graduated onto some fancy-dan laser cut parts (available through ponoko, or you can grab the source from the github repo), but the principle is the same. I’ve attached the design in an EPS on a ponoko P1 sized board.

The parts just slide together, and then onto a length of brass tube (see parts list). The laser cut parts have nodes in them that will need a little filing to get them on. Just be careful because the acrylic is pretty brittle. It should all push-fit together, but if it gets too loose, a few dabs of glue will keep it together. I usually put a bead of glue around the hole in the stabiliser, and then another couple of dots around the hole in the final spacer ring.

The sequence is, from bottom to top:

  1. Big stabiliser
  2. Empty bearing
  3. Spacer ring
  4. Bearing with straight cord hanger arm
  5. Spacer ring
  6. Bearing with offset cord hanger arm
  7. Spacer ring (this is the one I glue)
  8. And a plywood ring as a decorative touch

Step 16: Add cord and counterweights

The length of the cord will obviously dictate the size of your drawing. Make your cords long enough to stretch at least from your sprocket to the opposite corner of your biggest drawing paper sheet, when it’s mounted. Don’t forget to leave a couple of inches to tie/clip your counterweights on with. Just push one end into the clips on the gondola.

I use some bolts with washers on them as counterweights, but you can use anything – bags of change are a good alternative. The exact weight isn’t critical at all – this is not a finely balanced machine. The object is to have the gondola hang naturally in the upper-middle of the machine’s drawing area. My weights are around 150 grams each.

After this, you may even wear your gondola with beaded cord as if it is a steampunk arc reactor medallion. I often do, and feel very powerful at it. POW! TAKE THAT, BAD GUYS!

Ahem… Or you can just put it on the machine, draping the cords over the sprockets. You’ll need to figure out a neat way of avoiding the cables if you have front-mounted motors like me.

Step 17: Back to the drawing board

Ok, the last bits of configuration then:

  1. Measure your machine size
  2. Find your home point

Use the diagram attached to this step, and draw lines on your drawing surface in the places marked.

It’s important that the lines are all square and parallel, and your measurements are accurate. You can’t hope to get good results if you don’t have it marked out properly. As they say: Proper Preparation Prevents Poor Polargraphs. Don’t they?

Ok, so measure your machine width, in mm. This is the distance between the closest points of your sprockets. Measure from the teeth rather than from the rim. It should really be from the point where the cord hangs, but that changes all the time, so this’ll do.

Now draw a line for the top edge of your machine. It should run exactly in between your sprockets, between the two motor shafts.

Draw another horizontal line, exactly 120mm lower than your top edge you just drew. This is where you’ll put the top edge of your page. You can’t expect to draw much higher than this.

Draw a vertical line down the exact centre of your machine. Where this vertical line crosses your top edge of page line is your home point. The machine knows where it is, you know where it is. You both agree, and it’s where everything starts from.

Step 18: Finish configuring your controller

Start the controller again, and change to the setup tab.

Set:
machine width
machine height

entering the values you just measured, in millimetres. Height isn’t actually that important since it doesn’t affect the geometry, but it does affect how big it appears on your screen, so make it accurate if you can. You will be able to see the machine changing size on screen as you adjust these values.

You can also change the page width here, and the page position. Unless you have a much wider machine than this, leave page pos y as 120 though.

Other than that, page size and position is a purely visual aid to let you size your drawing properly. You can centre the page horizontally with the centre pagebutton.

The home point has a default position that is where you marked it on your board in the last step, that is, halfway across the top edge of your machine. Click centre homepoint to reset if it goes astray, and you can set it to anywhere you like if you don’t want it there (for whatever reason).

Now save properties again so you don’t have to enter this again!

Advanced editing
If you are using different motors, or different sprockets, change:

  • stepsPerRev: This is how many steps your motors have per revolution. Well, it’s actually _double_ that, because I’m using an interleaved step style in the software – it creates kind of intermediate steps. My stepper motors have 400 steps per rev, so I enter 800. Yours are probably 200, so you should enter 400.
  • mmPerRev: This is how much cord is extended per revolution. It is essentially the circumference of the sprockets, though with these beaded cords, it’s actually the length of 8 bead sections.
  • step multiplier: (not shown on the pic…) This is how many microsteps the machine can make between your big steps. For this machine, set to 1.

If you are changing these settings, you are best off restarting the app afterwards. There’s a lot of other calculations based on these figures, so a fresh start is safer.

Step 19: Upload your measurements to the machine

So now you should see the size has changed on-screen so the controller knows what the real size of your machine is. But the machine itself doesn’t!

You need to upload it by going on the setup tab, you might already be there, and clickking Upload machine spec. This saves the new size into EEPROM on the arduino, so it’ll stay there even when the power is lost. Unless you change the sizes, this is the only time you have to do that. Page size isn’t relevant here, only machine size.

If you’re curious (and why wouldn’t you be?) Download machine spec does the opposite – it set’s the machine size in the controller to be whatever the hardware has saved. This might be useful if you delete your configuration file sizes and don’t want to measure it all again.

But remember that the configuration file doesn’t ever get updated until you click save properties. So remember that if you make changes you want to keep.

Step 20: Now really make it move!

You need to calibrate the machine before each drawing session. This involves telling it where the pen is. You do this by clicking Set home on the Input tab and then physically moving the gondola so that it directly over the home point that you worked out earlier.

Clicking Set home locks the motors, it applies power, so they will hold the gondola there for as long as you want.

AND THAT’S IT!

Use Move pen to point to move the gondola around the drawing surface. The noise should be smooth, and the motion also. If you find your motors slip – most likely near the extremes of the the surface, or when you’re moving fast – you’ll need to recalibrate. As soon as the actual position of the gondola gets out of sync with where the machine thinks it is, then your geometry is all off and your drawings will be distorted.

The standard maximum speed is 600 steps per second, and the acceleration is 700 steps per second (per second). Change these values by using the number spinners on the setup tab, and then clicking send speed. These speed change commands also skip right to the front of the queue too – they’re priority, you can see them in cyan in the queue.

Step 21: Work with images

So that’s the hard bit done – now load a drawing, select an area to draw, and choose a drawing style.

  • On Input tab, click load image and browse to an image to try. Some work better than others, but it’s all to taste, so just experiment.
  • If your image doesn’t show up right away, it might be off the screen somewhere, or too small. Click move image and you should see a ghost version of your image hovering under your mouse. Click in the centre of your machine to place it there, and click move image again to move out of that mode.
  • Drag resize image to control how big the image is.
  • Click Select Area and drag a box around the area you want to draw.
  • Once you’ve selected an area, the view will automatically switch to hiding the image, and showing the density preview. Use the smaller view buttons in the bottom of the control panel to show the image or hide the density preview.
  • The density preview is designed to show what detail is being captured. The circles are not representative of the shapes that will be drawn, but are representative of their intended position, size and brightness.
  • Drag the number spinner for grid size to change the size of the “pixels”, bearing in mind that smaller ones take longer to draw (actually they are faster individually, but there are more of them).
  • Drag the number spinner for sample area to change the contrast of your image. This is the size of the area that is sampled when choosing the density (pixel sample area). I find I get the best results with a sample area just bigger than my grid size.

Remember, that once you’ve found a setting you like, you can save it to the properties configuration file by clicking save properties. If you don’t, it’ll all disappear when you restart and you will burst into tears.

Step 22: Choose a pixel style

Currently there are four pixel styles.

  • Shade Square wave – the standard. Pixel density is translated into a square wave pattern. Darker pixel = more waves = more ink.
  • Shade Scaled square wave – the half-tone effect. Instead of changing the number of waves, this one changes the size of the square that gets drawn. Darker pixel = big pixel = more ink.
  • Shade Solid – used for multi-layer chroma keying effects. This shades every pixel at maximum density, no variation.
  • Shade scribble – noisy effect. This is like a randomised pixel – a number of lines are drawn, but their direction and length are random (within the boundary of the pixel). Darker pixel = more lines = more ink.

Step 23: Load it up and get scribbling!

Load a pen in the gondola just by sticking it in with a bit of blu-tack, so the tip peeps out just a bit.

Stick a piece of paper onto the surface.

Home your gondola.

Click the “render” button for the kind of pixel you want.  Watch in amazement!

I’ve had best success with non-bleeding pens and paper.  I like using a very smooth paper like bristol board, along with hard-tipped fineliner pens.  Here in the UK I can buy these ZIG Millennium pens quite easily, and they’re really good. Pigma MICRON seems to be a popular US pen in the same kind of vein.

For coarser drawings, a thicker tip is good, I’ve used regular sharpies regularly, and though they bleed badly, they are vibrant and solid.

Step 24: Pen lift servo

If you fasten a little servo motor to the gondola, you can use it to lift the pen off the page.  There are two servo connectors on the motorshield, if you connect up SER1, then this will respond to commands sent to the machine.  I just use the control horn to poke through the gondola and lever against the surface.

The commands can be issued manually by using # or ~ to raise or lower the pen.  This is not very subtle, but it works well enough to prevent the pen from leaving a big bleedy mark at the end of the drawing. These commands are automatically added to the beginning and the end of the queue when you do a drawings.

Step 25: Pen thickness

The size of the pen tip controls how many waves the machine can fit into one pixel.  If you have a pixel that is 20mm square, and you have a 1mm pen tip, then you can only fit a maximum of 20 lines in before it’s at it’s maximum density.  Adding more ink then won’t make it any darker.

If you then swap out the pen and put in one with a 0.5mm tip, 20 lines will no longer completely fill in the pixel, now it will require 40 lines to fill it.  The machine works out the maximum possible density based on what sized pen you tell it you’ve installed.

You can change the pen width on the setup tab, by changing the value of pen tip size and clicking send pen tip size.  The tip size is not saved in the machine, it needs to be resent every time the machine is restarted, which is why the value is pre-loaded in the queue when you restart the controller.

Test pen widths
Rather than rely on manufacturers descriptions of pen tip width, there is a kind of calibration function to test pen widths too, this draws a sequence of pixels at maximum density, but it increments the pen width setting between each one, so you can try to narrow down what pen tip thickness gives you the deepest density you want.

There are three settings on that setup tab that control the size of the test swatch:

Pen test start tip – this is the tip size for the very first square and should be low.
Pen test end tip – this is the biggest tip size the machine will try.
Pen test inc size – this is the size of the increments that the machine will make to get from the start tip size to the end tip size.

If it was set to start:0.6, end: 2.0 and increment: 0.1, the machine will draw the first pixel as if it has a 0.6mm sized pen, then draw more, each time incrementing by 0.1mm, until it is 2mm.

Once you’ve decided which square you want to be your darkest, set the pen tip width to the setting required and save properties.

Step 26: Vector graphics drawing

With the new software (controller v1+ and server_a1), came vector drawing capabilities that make this machine even more useful.

Using Inkscape
All the paths need to be separate in the SVG file.  Text needs to be converted into paths.  You can do this by selecting everything and going to Path->Object To Path (this will convert any shapes like letters into outlines), and then select them all again and do Path->Break Apart (this breaks up any letters that have more than one outline in them).  You might find it useful after that to change the fill colour to empty (click on the empty swatch at the bottom), and set the outline to be black (shift-click on the black swatch at the bottom).  Save it.

Click load vector from the input control panel, and choose your SVG file.  If you can’t see your vector, click “move vector” and you should see it floating under your mouse as you move it.  Click again to place the SVG.  You can resize by dragging the “resize vector” number spinner.  Here 100 represents full size, that is 1px in inkscape equals 1mm on the machine.

Only lines that are entirely within the page area will be processed by the controller.

Now click render vector to convert the line art into polargraph commands and load them all into the command queue.  For vector work, the move direct command is used to tell the machine where to move, and it will always draw in a straight line on the board. The down side is that it’s a lot slower because it basically chops the line into dozens of smaller lines, and has to do a lot more calculations continuously.

If you hide the vector lines (show vector) you can see the actual lines that are stored up in the command queue previewed (show queue preview).