Introduction: Balancing Instructable Robot

About: I am currently doing my BE in mechanical engineering but im more interested in physics and robotics and such stuff.I am new here hope u like my instructables!!!

In this Instructable I wanted to show to you how to make a self balancing robot. What makes it unique is that its exterior is made to look like the Instructables Robot. Internally it works in the principle of PID, it is a very popular control system for maintaining a variable from fluctuating. In this instructable I have used the MPU6050 which is a gyroscope and an accelerometer in a single package. The gyroscope is used to find the angular orientation and the acceleration. For our application we just need the gyroscope data. To start off I will discuss the various applications and knowledge obtained from this project. Please vote for my entry in the "Instructable Robot Contest" if you find this instructable good.

Project-Based Learnings:

  • Knowledge of how to use the MPU6050 module.

  • How to implement the data to balance the robot.

  • How to implement control systems to your projects.

____________________________________________

Applications:

    ____________________________________________

    Proportional-Integral-Derivative System Advantages:

    • This Control System should be used when the controlled element needs precise control.

    • This balancing robot can be easily made by a Novice Arduino Programmer using this Control System.

    • The tuned PID system is very flexible over a range of environments (i.e. balancing even when weight is added).

    ____________________________________________

    This control system's efficiency depends on the tuning of three variables namely the Proportional constant, Integral constant and Derivative constant, So once you tune the variables accurate control of the robot is achieved. I have provided most of the instructions for making the robot. This robot is in the intermediate level of robotics so beginners shouldn't get frustrated because it for very challenging for Me!!!

    Step 1: Parts & Materials

    The material needed to make this balancing robot can be grouped into two categories as shown below:

    Electronic Components:

    ____________________________________________

    Other Parts:

    ____________________________________________

    Please note that I have not used Acrylic Sheet as mentioned but Hylam Sheet(Bakelite Sheet). It is very much similar to acrylic but more rigid and easier to cut. It is commonly used in India for Switchboard Boxes. It may or may not be available in your Country so I mentioned it as an Acrylic Sheet.

    Step 2: Making the Robot Chassis

    This step is for making the chassis parts which form the base of the robot. As I mentioned earlier I have not used the acrylic sheet but a Hylam Sheet. The base consists of two strips to which the motor is mounted and a rectangular base on which these strips are mounted in perpendicular. To prepare the Body follow these instructions.

    Step 1:

    In this Step, I cut the strips that support the motors. I've cut them with dimensions of 2cm by 8cm. This material is much stronger than the acrylic sheet.

    Step 2:

    When the sketch has been drawn, cut the pieces out using a Hacksaw or a Jigsaw cutter. The cutting process will produce a lot of dust. Cut the sheet in a well ventilated room.

    Step 3:

    Next comes the base which supports the two strips. Draw a Rectangle of about 14cm in width and 18cm in length. Then draw the mid-line for the base along the width as shown in the diagram. This line will serve as a guide line for fitting the strips.

    Step 4:

    Cut out this drawn part using the Hacksaw or the Jigsaw cutter as shown. Use a marker for reference and clean the board later to remove the marker lines.

    Step 5:

    Next draw two vertical lines as shown in the diagram. These lines are used for aligning the clamps of the motor. With this step we have finally completed the chassis components. The next step deals with the motor and wheel assembly.

    Step 3: Attaching the Motors

    After cutting the chassis components next comes, assembling the motors with the strips we cut earlier, then attaching these strips to the bigger piece we cut using L-clamps. The motors need holes for the wires to pass through so they should also be cut in addition to the clamp holes.

    Step 6:

    Cut some double sided tape and stick it to one end of the strip as shown in the diagram. This method involves no clamping with nuts and bolts.

    Step 7:

    Remove the double sided tape top paper cover to reveal the other adhesive side of the tape. Place the motor on the tape so that it is parallel to the strip.

    Step 8:

    Then tighten the motor to the strip using cable ties. This ensure that the motor is firmly clamped to the strip.

    Step 9:

    Cut off the excess and Cable tie wire using either a wire stripper or scissors.

    Step 10:

    Fit the wheel into the motor and tighten the joint using a screw as shown.

    ____________________________________________

    There you go you have completed mounting the motor onto the strip. Repeat the procedure for the second strip and you would have obtained two of the Instructable strong>Robot's legs with wheels. The final diagram shows the completed legs.

    Step 4: Finishing the Chassis

    With this page we will complete the chassis of the Instructable Robot. The prepared chassis is very rigid and stable and is capable of handling the weight of the battery and the electronics. The motors in the pictures are dirty, please excuse it since I have been using them for my other projects.

    Step 11:

    In this step I use a L-Clamp which is basically a piece I have in my childhood engineering set. You will be easily able to find out L-Clamps, a link to some clamps is also provided. Anyway place the clamp on top of the free end of the strip. Then mark the holes of the clamp using a marker.

    Step 12:

    Repeat the same procedure for the other motor strip. You will obtain two strips with holes marked and ready for drilling.

    Step 13:

    This step shows Me drilling the holes on both the motor strips. The holes are made by a 4mm drill-bit.

    Step 14:

    Before mounting the clamps on the strips, place the clamps on the main board as shown in the diagram. Then mark the holes using a marker for drilling.

    Step 15:

    This step shows Me drilling the holes on the base of the chassis.

    Note:

    I only drilled two holes in the previous picture but another hole is needed for the wires to pass through the chassis. So please make another hole.

    Step 16:

    On completing all these steps you will obtain the following assembled parts as shown in the diagram.

    Step 17:

    I have not provided any pictures of tightening the nuts and bots but once screwed in, it will look as shown in the diagram.

    ____________________________________________

    After completing all these steps the finished chassis will look as shown in the last Figure. The chassis houses the Battery, Ultrasonic Sensors and The Electronics.This ends the mechanical work needed for this project.

    Step 5: Mounting the Motors to the Driver.

    Lets move on to wiring the electronics for the robot. The next few steps will have some Fritzing sketches, some additional images and a little description of the module we are using. So that you are aware of both the working and how to operate the module. The steps below show us how to wire the motors and fix the battery.

    Step 18:

    In this step I solder the wires to the motor terminals.

    Step 19:

    Pass the wires through the extra hole we drilled in the clamp as shown in the figure.

    Step 20:

    Place the module on the base and mark the holes using a marker.

    Step 21:

    In this step I make the using using a 4mm Drill bit.

    Step 22:

    Fix the module to the base using some nuts and bolts. This firmly fixes the module to the base.

    Step 23:

    Connect the motors to the motor terminals of the module and the 9V battery connector to the Power terminals of the Module.

    Step 24:

    Finally screw the terminals using a Screw-driver so that the wires are fixed.

    Step 6: Mounting the Arduino

    This involves mounting the Gyroscope sensor module and the Arduino UNO board to the base of the robot.

    Step 25:

    Firstly mark the holes for the Arduino module on the base using a marker.

    Step 26:

    Drill the holes using the same 4mm Drill bit. For the Arduino three holes are enough for mounting to the base.

    Step 27:

    This steps shows the holes drilled onto the base of the robot. Please ignore the extra holes they are from my previous incorrect mounting attempts.

    Step 28:

    Finally screw the Arduino to the base using some screws as shown in the figure.

    Step 29:

    Place the Gyroscope module on the base and mark the holes using the marker.

    Step 30:

    Drill the holes and mount the module as shown in the diagram. I have also provided a side view of the module mounted to the base. The more elevated the module the better so use long screws as shown.

    ____________________________________________

    This concludes the mounting of the motor driver module, the gyroscope and the Arduino UNO. I have provided the motor driver wiring diagram please use this diagram. Connect the respective pins using the jumper wires I couldn't show the steps for that but I think I have provided enough images. The final image shows the chassis with the motor driver board and the battery attached.

    Step 7: Increase the Arduino Power Pins

    Power Pin Expander:

    Since this project involves a lot of power pins. I had to make a power pin expander. This is not my own idea but I got it from another Instructable.Check out the maker of this idea "Arduino Micro Power Expansion Shield" by Wenzej. Anyway I have added a mini Instructable for expanding the Power pins of the Arduino.

    Parts Needed:

    Making The Expander:

    Step 31:

    First solder the 4-Pin Connector as shown in the diagram.

    Step 32:

    Remove the plastic of the 4-Pin Connector. This needs to be done carefully as the metal headers may break off.

    Step 33:

    Insert the female header strips into the strip board as shown in the diagram.

    Step 34:

    Solder the Power rails as shown in the diagram.

    ____________________________________________

    Then you are done. The final image shows the finished module and the other image shows the module inserted into the Arduino UNO power pins.

    Step 8: Inserting the Potentiometers

    Why I used Tuning Pots:

    As you know this project uses PID Control. So we need to set the values of the proportional, derivative and integral constant. So I made this easy way with which the values can be set easily. Basically I use potentiometers and the analog pins of the Arduino to set the value. The potentiometer gives us a value of 0V to 5V which is then converted into values from 0 to 255. The following code is responsible for this conversion.

    Kp = map(analogRead(A0), 0, 1024, 0, 200);
    Ki = map(analogRead(A1), 0, 1024, 0, 20);
    Kd = map(analogRead(A2), 0, 1024, 0, 20);

    So using the map command you can set the values with just the turn of the potentiometer you can dynamically set the values for the constants. This saves you the hassle of changing the values of the constants in the code and reprogramming them repetitively. I have included a Fritzing sketch of the circuit for the potentiometers.

    Assembling the Tuning Pots:

    Step 35:

    Mark the holes where the potentiometers need to be inserted using a marker.

    Step 36:

    Drill holes in the marked base using a 12mm drill bit.

    Step 37:

    Before we insert the potentiometer. We need to make holes for the extra flange coming out from the potentiometer. The use of this flange is to prevent the potentiometer from rotating. Mark the flange location with a marker.

    Step 38:

    Make 2mm drills in these spots for the potentiometer flanges.

    Step 39:

    Inset the potentiometers into the holes and finally tighten the nut in the potentiometer to affix it to the bottom side of the base.

    Step 40:

    Fix the knobs into the potentiometer shafts to give it a more aesthetic look.

    Step 41:

    Wire up the power pins to both ends of the potentiometers as shown in the diagram.

    Step 42:

    Finally wire the Wiper pin (middle pin) to the analog pins of the Arduino. The final diagram shows the completed wired module.

    ____________________________________________

    I have also provided a sample code to test the potentiometer to check they are working properly. Wire the circuit as shown in the fritzing sketch and you will be able to adjust the PID constants and the serial monitor will show the constant values. If all goes well you will obtain an output similar to the final image.

    Step 9: Connecting the Motor Driver

    Introduction to the L298:

    The motor driver I have used for this project uses the L298 Dual H-Bridge Motor Driver. The reason I chose this board was its advantages over other drivers. The L298 IC has an amperage of 2A. Another Reason is that I have burnt quite a few L293 Motor drivers because of its low Ampere capacity. Lets start off with the pins of the L298 Board.

    The L298 Board Pins:

    Enable Pin (ENA and ENB): This pin needs to be set to HIGH or the board won't process the command given through the other pins. So this pin permits the IC to receive commands from the Arduino when it is turned HIGH.

    Current Sense Pin (CSA and CSB): The current sense pins in general can be tied to ground, but one can
    insert low value resistor, whose voltage reading is proportional to current. Here we just tie them to ground. Note that your board may or may not contain this pin, if it doesn't just forget about this pin.

    Input Pins (IN1,IN2, IN3 and IN4): As the name suggests these pins go to the Arduino. Where IN1 and IN2 belong to Channel A and IN3 and IN4 belong to Channel B. The truth table for operating two motors are as follows.

    Motor AMotor B
    IN1IN2OUTPUTIN3IN4OUTPUT
    10FORWARD10FORWARD
    01REVERSE01REVERSE
    00STOP00STOP

    That concludes my introduction to the l298 motor driver board. This board can be bought in this link or it can be made, I haven't done a tutorial on how to make your own maybe soon. I have provided a Wiring diagram for connecting the L298 to the Arduino.The final diagram shows the connected jumper wires on the base of the robot.

    ____________________________________________

    Since both the motors are driven in the same direction we connect it to the same analog pin of the Arduino. Since the Arduino only contains six analog pins, the motors are driven by the same pin.

    Step 10: Connecting the MPU6050

    About the MPU6050:

    The MPU6050 is one of the best and cheapest accelerometer and gyroscope modules you can get out there. The functions performed for the prices is just outstanding.The module has on-board Digital Motion Processor™ (DMP™) capable of processing complex 9-axis Motion-Fusion algorithms. The variable that are required for this project are just the yaw, pitch and roll, they are used to describe the rotations occurring along the three axises of the robot.

    The MPU6050 can be purchased for cheap in this link. I have also provided a Fritzing Sketch for connecting the MPU6050. I have provided an example code with which the MPU6050 can be tested. The Final image shows the MPU6050 wired to the Arduino in the robot.

    MPU6050 Important Pins:

    Power Pin (Vcc):

    Used to supply positive voltage to the MPU6050 module.

    Ground Pin (GND):

    Connects to the ground pin of the Arduino.

    SDA & SCL Pins:

    Used to establish a connection with the Arduino analog pins A4 and A5 to receive the accelerometer and gyroscope data.

    Interrupt Pin (INT):

    This pin instructs the Arduino when to read the data from the module, this pin instructs the Arduino only when the values change.

    ____________________________________________

    I have provided a small code to test the module before entering the main code. This code is made by Jeff Rowberg So just include the library using the following steps:

    Loading the Library:

    1. So open the Arduino IDE software.
    2. Go to Sketch => Import Library => Add Library.
    3. Select the downloaded library which I have named "i2cdevlibmaster" and click ok.
    4. Now that the library is loaded go to File => Examples => i2cdevlibmaster => Arduino => MPU6050 => Examples => MPU6050_DMP6.
    5. Just compile the sketch and upload it to test the MPU6050 Module.
    6. If everything goes well you will obtain the same output as the final image.

    Step 11: Finishing Touches

    We have almost finished the business end of the robot. These steps summarize the power supply for the boards.

    Step 43:

    Put some double side tape on the base as shown in the diagram. Its more simpler than bolting the batteries to the base.

    Step 44:

    Stick the batteries onto the double sided tape. Insert the 9V power connector into the Arduino board.

    Step 45:

    Insert the power connectors on both the 9V batteries and the power is supplied to all the modules.

    ____________________________________________

    The next step contains the code as well as additional details used to make the robot. Just upload the code into the Arduino and connect the power supplies to the respective boards. After some tuning of the PID constants you can obtain great results. I have provided a video in the next step.

    Step 12: Uploading the Code

    Once you have made the robot finally its time to upload the code and give the robot a test run. I have provided the completed code just upload it and experiment with the PID constant to achieve proper balancing.

    CODE:

    #include "I2Cdev.h"
    
    #include "MPU6050_6Axis_MotionApps20.h"
    //#include "MPU6050.h" // not necessary if using MotionApps include file
    
    // Arduino Wire library is required if I2Cdev I2CDEV_ARDUINO_WIRE implementation
    // is used in I2Cdev.h
    #if I2CDEV_IMPLEMENTATION == I2CDEV_ARDUINO_WIRE
    #include "Wire.h"
    #endif
    
    MPU6050 mpu;
    #define OUTPUT_READABLE_YAWPITCHROLL
    
    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
    VectorInt16 aa; // [x, y, z] accel sensor measurements
    VectorInt16 aaReal; // [x, y, z] gravity-free accel sensor measurements
    VectorInt16 aaWorld; // [x, y, z] world-frame accel sensor measurements
    VectorFloat gravity; // [x, y, z] gravity vector
    float euler[3]; // [psi, theta, phi] Euler angle container
    float ypr[3]; // [yaw, pitch, roll] yaw/pitch/roll container and gravity vector
    
    static int pot1Pin = A0;
    static int pot2Pin = A1;
    static int pot3Pin = A2;
    float Kp = 0;
    float Ki = 0;
    float Kd = 0;
    float targetAngle = 8.5;
    float currAngle = 0;
    float pTerm = 0;
    float iTerm = 0;
    float dTerm = 0;
    float integrated_error = 0;
    float last_error = 0;
    float K = 1;
    // ================================================================
    // === INTERRUPT DETECTION ROUTINE ===
    // ================================================================
    
    volatile bool mpuInterrupt = false; // indicates whether MPU interrupt pin has gone high
    void dmpDataReady() {
        mpuInterrupt = true;
    }
    
    // ================================================================
    // === INITIAL SETUP ===
    // ================================================================
    
    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
    
        Serial.begin(115200);
        while (!Serial); 
        Serial.println(F("Initializing I2C devices..."));
        mpu.initialize();
        Serial.println(F("Testing device connections..."));
        Serial.println(mpu.testConnection() ? F("MPU6050 connection successful") : F("MPU6050 connection failed"));
        Serial.println(F("Initializing DMP..."));
        devStatus = mpu.dmpInitialize();
        mpu.setXGyroOffset(220);
        mpu.setYGyroOffset(76);
        mpu.setZGyroOffset(-85);
        mpu.setZAccelOffset(1788); // 1688 factory default for my test chip
        if (devStatus == 0) {
            Serial.println(F("Enabling DMP..."));
            mpu.setDMPEnabled(true);
            Serial.println(F("Enabling interrupt detection (Arduino external interrupt 0)..."));
            attachInterrupt(0, dmpDataReady, RISING);
            mpuIntStatus = mpu.getIntStatus();
            Serial.println(F("DMP ready! Waiting for first interrupt..."));
            dmpReady = true;
            packetSize = mpu.dmpGetFIFOPacketSize();
        } else {
            Serial.print(F("DMP Initialization failed (code "));
            Serial.print(devStatus);
            Serial.println(F(")"));
        }
        pinMode(3, OUTPUT);
        pinMode(4, OUTPUT);
        pinMode(pot3Pin, INPUT);
        pinMode(pot1Pin, INPUT);
        pinMode(pot2Pin, INPUT);
        pinMode(A3, OUTPUT);
        pinMode(12,OUTPUT);
        pinMode(13,OUTPUT);
      }
    
    // ================================================================
    // === MAIN PROGRAM LOOP ===
    // ================================================================
    
    void loop() {
        if (!dmpReady) return;
        while (!mpuInterrupt && fifoCount < packetSize) {
        }
        mpuInterrupt = false;
        mpuIntStatus = mpu.getIntStatus();
        fifoCount = mpu.getFIFOCount();
        if ((mpuIntStatus & 0x10) || fifoCount == 1024) {
            mpu.resetFIFO();
            Serial.println(F("FIFO overflow!"));
        } else if (mpuIntStatus & 0x02) {
            while (fifoCount < packetSize) fifoCount = mpu.getFIFOCount();
            mpu.getFIFOBytes(fifoBuffer, packetSize);
            fifoCount -= packetSize;
    
    #ifdef OUTPUT_READABLE_YAWPITCHROLL
                mpu.dmpGetQuaternion(&q, fifoBuffer);
                mpu.dmpGetGravity(&gravity, &q);
                mpu.dmpGetYawPitchRoll(ypr, &q, &gravity);
                Serial.print("ypr\t");
                Serial.print(ypr[0] * 180/M_PI);
                Serial.print("\t");
                Serial.print(ypr[1] * 180/M_PI);
                Serial.print("\t");
                Serial.println(ypr[2] * 180/M_PI);
    #endif
            Kp = map(analogRead(pot1Pin), 0, 1024, 0, 255);
            Ki = map(analogRead(pot2Pin), 0, 1024, 0, 20);
            Kd = map(analogRead(pot3Pin), 0, 1024, 0, 20);
            Serial.print("Kp: ");
            Serial.print(Kp);
            Serial.print("        Ki: ");
            Serial.print(Ki);
            Serial.print("        Kd: ");
            Serial.println(Kd);
            currAngle = (ypr[1] * 180/M_PI);
            Drive_Motor(updateSpeed());
            Serial.print("speed: ");
            Serial.println(updateSpeed());
        }
    }
    
    float updateSpeed() {
      float error = targetAngle - currAngle;
      pTerm = Kp * error;
      integrated_error += error;
      iTerm = Ki * constrain(integrated_error, -50, 50);
      dTerm = Kd * (error - last_error);
      last_error = error;
      return -constrain(K*(pTerm + iTerm + dTerm), -255, 255);
    }
    
    float Drive_Motor(float torque)  {
      Serial.print("torque: ");
      Serial.println(torque);
      if (torque >= 0)  {                                        // drive motors forward
        digitalWrite(3, LOW);
        digitalWrite(4, HIGH);
        digitalWrite(12, LOW);
        digitalWrite(13, HIGH);
      }  else {                                                  // drive motors backward
        digitalWrite(3, HIGH);
        digitalWrite(4, LOW);
        digitalWrite(12, HIGH);
        digitalWrite(13, LOW);
        torque = abs(torque);
      }
      analogWrite(A3,torque);  
    }
    

    If the connections are exactly followed you will get the motors turning in at least one direction, if it doesn't go back to the previous steps and check the connections again. When all goes well you will obtain results as shown in the Test Video above. Next I will give some instructions on how to get decent results from the PID constants.

    Tuning the PID Constants:

    1. Firstly increase the proportional value by slowly turning the proportional potentiometer knob. Test the balancing of the robot for every turn of the potentiometer.
    2. Then when the robot oscillates from side to side like a pendulum then you increase the Integral and Derivative constant potentiometers.
    3. This is the most difficult part because only at certain values can effective balancing be achieved in the robot. My suggestion would be to vary the values and determining the ideal values for your robot. Please note that these values vary from robot to robot.

    ____________________________________________

    Please note that this is my first successful balancing robot. So I have got the robot balancing but there surely is room for improvement. In the future I want to make a more precise PID controlled balancing robot with additional features maybe in the future.

    Step 13: Cutting the Body

    As you know already the base of my robot is about 17 by 12.5cms so cut the parts as given in the pictures provided.

    Step 46:

    Cut the first image into two separate sides. Please note that one side is the mirror image of the other side. After this step you will have two cut pieces.

    Step 47:

    Cut the second image to the dimensions provided. This piece will serve as the back of the Instructable robot.

    Step 48:

    Finally cut the the third image which serves as the front and the top of the robot.

    Step 49:

    Cut the individual pieces out with scissors.

    Step 50:

    Place the cut pieces as shown in the figure and tape the pieces up using clear tape.

    Step 51:

    Place the other mirror image of the first cut piece like as shown in the figure and tape it up.

    Step 52:

    Finally tape the front piece and you are done with the body sides.

    Step 53:

    Fold up the pieces into a square, tape the final side into a box. tape all the sides to make it rigid.

    Step 54:

    Fold the top flap to make the top base. Stick another rectangle of dimensions 8.5 to 17 cm and stick it to the top of the robot.

    Step 55:

    Cut up six sides of squares of 10 cm and tape them up to form a box.

    Step 56:

    Put some double sided tape on top of the base and stick the prepared head into the base.

    Step 57:

    Finally draw the robots features using the sketches to finish the robot and stick two toothpicks on two sides of the head.

    Step 58:

    Make two yellow cylinders to cover the robots motors and constitute the legs of the robot.

    Step 59:

    Stick the robot cardboard body to the mechanical base of the robot using some clear tape and then you are done.

    Step 60:

    Open the robot up, turn on the power supply, close up the robot and see your balancing robot in action.

    Step 14: You're Done!!!!!

    Finally we have reached the end of this project. Personally I had to face many difficulties to complete this project but after I completed first Balancing robot I felt it was all worth it. I have learn't a lot from this project and I hope you have as well. I have provided a video showing the final performance of the robot. I look forward to my next instructable. If you have any comments or suggestions about the project please do ask. If you find this project good please vote for my project. Till next time Bye!!

    Instructables Robot Contest

    Participated in the
    Instructables Robot Contest