Trybotics Logo

DIY Self Balancing Robot DC Motors Bluetooth HC-05

DESCRIPTION

After being inspired by the MINI Segway hoverboard and other self balancing scooters from Segway, I always wanted to build something similar. Thinking for while, I decided to build a Self Balancing Robot using Arduino. This way I would be able to grasp the underlying concept behind all these scooters and also learn how PID algorithm works.

Once I started building, I realised that this bot is a bit of a challenge to build. There are so many options to select from and hence the confusions start right from selecting the motors and remains till tuning PID values. And there are so many things to consider like type of battery, position of battery, wheel grip, type of motor driver, maintaining the CoG (Centre of gravity) and much more.

But let me break it to you, once you build it you will agree that it’s not as hard as it sounds to be. So let’s face it, in this tutorial I will document my experience in building the self balancing robot. You might be an absolute beginner who is just getting started or might have landed up here after a long frustration of not getting your bot to work. This place aims to be your final destination. So let’s get started......

Description:

Before I tell you all the options for building the bot let me list the items that I have used in this project :

Arduino UNO

Geared DC motors (Yellow coloured)

L298N Motor Driver

ModuleMPU6050

a pair of wheels

9V Li-ion Battery

Connecting wires

Chassis

Controller: The controller that I have used here is Arduino UNO, why because it is simply easy to use. You can also use a Arduino Nano or Arduino mini but I would recommend you to stick with UNO since we can program it directly without any external hardware.

Motors: The best choice of motor that you can use for a self balancing robot, without a doubt will be Stepper motor. But To keep things simple I have used a DC gear motor. Yes it is not mandatory to have a stepper; the bot works fine with these cheap commonly available yellow coloured DC gear motors as well. Motor Driver: If you have selected the DC gear motors like mine then you can either use the L298N driver module like me, or even a L293D should work just fine. Learn more about controlling DC motor using L293D and Arduino. Wheels: Do not under estimate these guys; I had a tough time figuring out that the problem was with my wheels. So make sure your wheels have good grip over the floor you are using. Watch closely, your grip should never allow your wheels to skit on the floor.

Accelerometer and Gyroscope: The best choice of Accelerometer and Gyroscope for your bot will be the MPU6050. So do not attempt to build one with a normal Accelerometer like ADXL345 or something like that, it just won’t work. You will know why at the end of this article. You can also check our dedicated article on using MPU6050 with Arduino.

Battery: We need a battery that is as light as possible and the operating voltage should be more than 5V so that we can power our Arduino directly without a boost module. So the ideal choice will be a 7.4V Li-polymer battery. Here, since I had a 9V Li-ion battery readily available I have used it. But remember a Li-po is advantageous than Li-ion.

Chassis: Another place where you should not compromise is with your bots chassis. You can use cardboard, wood, plastic anything that you are good with. But, just make sure the chassis is sturdy and should not wiggle when the bot is trying to balance.

Description:

Description:

Making the connections for this Arduino based Self balancing Robot is pretty simple. We just have to interface the MPU6050 with Arduino and connect the motors though the Motor driver module. The whole set-up is powered by the 9V li-ion battery. The circuit diagram for the same is shown below.

The Arduino and the L298N Motor driver module is directly powered through the Vin pin and the 12V terminal respectively. The on-board regulator on the Arduino board will convert the input 9V to 5V and the ATmega IC and MPU6050 will be powered by it. The DC motors can run from voltage 5V to 12V. But we will be connecting the 9V positive wire from battery to 12V input terminal of motor driver module. This will make the motors operate with 9V. The following table will list how the MPU6050 and L298N motor driver module is connected with Arduino.

The MPU6050 communicates with Arduino through I2C interface, so we use the SPI pins A4 and A5 of Arduino. The DC motors are connected to PWM pins D3,D9 D10 and D11 respectively. We need to connect them to PWM pins because we will be controlling the speed of the DC motor by varying the duty cycle of the PWM signals.

Description:

Now we have to program our Arduino UNO board to balance the robot. This is where all the magic happens; the concept behind it is simple. We have to check if the bot is leaning towards the front or towards the back using the MPU6050 and then if it’s leaning towards the front we have to rotate the wheels in forward direction and if it is leaning towards the back we have to rotate the wheels in the reverse direction.

At the same time we also have to control the speed at which wheels are rotating, if the bot is slightly disoriented from centre position the wheels rotate slowly and the speed increase as it gets more away from the centre position. To achieve this logic we use the PID algorithm, which has the centre position as set-point and the level of disorientation as the output.

To know the current position of the bot we use the MPU6050, which is a 6-axis accelerometer and gyroscope sensor combined. In order to get a reliable value of position from the sensor we need to use the value of both accelerometer and gyroscope, because the values from accelerometer has noise problems and the values from gyroscope tends to drift with time. So we have to combine both and get the value of yaw pitch and roll of our robot, of which we will use only the value of yaw.

Sounds bit of head reeling right? But worry not, thanks to the Arduino community we have readily available libraries that can perform the PID calculation and also get the value of yaw from the MPU6050. The library is developed by br3ttb and jrowberg respectively. Before proceeding download their libraries form the following link and add them to your Arduino lib directory.

https://github.com/br3ttb/Arduino-PID-Library/blob...
https://github.com/jrowberg/i2cdevlib/tree/master/...

Now, that we have the libraries added to our Arduino IDE. Let’s start programming for our Self balancing Robot. Like always the complete code for the Project is given at the end of this page, here I am just explaining the most important snippets in the code. A told earlier the code is build on top of the MPU6050 example code we are just going to optimize the code for our purpose and add the PID and control technique for our self balancing robot.

here is the self balancing Arduino Program :

http://www.mediafire.com/file/wlu3iilsvyiltbm/Arduino_Main_Program.ino/file

Description:

<p>#include "I2Cdev.h"</p><p>#include <Wire.h><wire.h></wire.h></p><p>#include <PID_v1.h></p><p>#include <SoftwareSerial.h></p><p>#include "MPU6050_6Axis_MotionApps20.h"</p><p><wire.h><pid_v1.h><softwareserial.h><digitalioperformance.h><ultrasonic.h></ultrasonic.h></digitalioperformance.h></softwareserial.h></pid_v1.h></wire.h></p><p>#define d_speed 1.5
#define d_dir 3     </p><p>#define IN1 11
#define IN2 10
#define IN3 9
#define IN4 3</p><p>char content = 'P';
int MotorAspeed, MotorBspeed;
float MOTORSLACK_A = 40;                   // Compensate for motor slack range (low PWM values which result in no motor engagement)
float MOTORSLACK_B = 40;
#define BALANCE_PID_MIN -255              // Define PID limits to match PWM max in reverse and foward
#define BALANCE_PID_MAX 255</p><p>MPU6050 mpu;</p><p>const int rxpin = 6;       //Bluetooth serial stuff
const int txpin = 5;
SoftwareSerial blue(rxpin, txpin);</p><p>//Ultrasonic ultrasonic(A0, A1);
//int distance;</p><p>// 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</p><p>// 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</p><p>/*********Tune these 4 values for your BOT*********/
double setpoint; //set the value when the bot is perpendicular to ground using serial monitor.
double originalSetpoint;
//Read the project documentation on circuitdigest.com to learn how to set these values
#define Kp  10 //Set this first
#define Kd  0.6 //Set this secound
#define Ki  160 //Finally set this</p><p>#define RKp  50 //Set this first
#define RKd 4//Set this secound
#define RKi  300 //Finally set this
/******End of values setting*********/
double ysetpoint;
double yoriginalSetpoint;
double input, yinput, youtput, output, Buffer[3];</p><p>PID pid(&input, &output, &setpoint, Kp, Ki, Kd, DIRECT);
PID rot(&yinput, &youtput, &ysetpoint, RKp, RKi, RKd, DIRECT);</p><p>volatile bool mpuInterrupt = false;     // indicates whether MPU interrupt pin has gone high
void dmpDataReady()
{
  mpuInterrupt = true;
}</p><p>void setup() {
  Serial.begin(115200);
  blue.begin(9600);
  blue.setTimeout(10);
  init_imu();           //initialiser le MPU6050
  initmot();            //initialiser les moteurs
  originalSetpoint = 176;  //consigne
  yoriginalSetpoint = 0.1;
  setpoint = originalSetpoint ;
  ysetpoint = yoriginalSetpoint ;
}</p><p>void loop() {
    getvalues();
    Bt_control();
    printval();
}</p><p>void init_imu() {
  // initialize device
  Serial.println(F("Initializing I2C devices..."));
  Wire.begin();
  TWBR = 24;
  mpu.initialize();</p><p>  // verify connection
  Serial.println(F("Testing device connections..."));
  Serial.println(mpu.testConnection() ? F("MPU6050 connection successful") : F("MPU6050 connection failed"));</p><p>  // load and configure the DMP
  devStatus = mpu.dmpInitialize();</p><p>  // supply your own gyro offsets here, scaled for min sensitivity
  mpu.setXGyroOffset(220);
  mpu.setYGyroOffset(76);
  mpu.setZGyroOffset(-85);
  mpu.setZAccelOffset(1688);</p><p>  // make sure it worked (returns 0 if so)
  if (devStatus == 0) {
    // turn on the DMP, now that it's ready
    Serial.println(F("Enabling DMP..."));
    mpu.setDMPEnabled(true);</p><p>    // enable Arduino interrupt detection
    Serial.println(F("Enabling interrupt detection (Arduino external interrupt 0)..."));
    attachInterrupt(0, dmpDataReady, RISING);
    mpuIntStatus = mpu.getIntStatus();</p><p>    // set our DMP Ready flag so the main loop() function knows it's okay to use it
    Serial.println(F("DMP ready! Waiting for first interrupt..."));
    dmpReady = true;</p><p>    // get expected DMP packet size for later comparison
    packetSize = mpu.dmpGetFIFOPacketSize();</p><p>    //setup PID
    pid.SetMode(AUTOMATIC);
    pid.SetSampleTime(10);
    pid.SetOutputLimits(-255, 255);
    rot.SetMode(AUTOMATIC);
    rot.SetSampleTime(10);
    rot.SetOutputLimits(-20, 20);
  }
  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(")"));
  }
}</p><p>void getvalues() {
  // if programming failed, don't try to do anything</p><p>  if (!dmpReady) return;</p><p>  // wait for MPU interrupt or extra packet(s) available
  while (!mpuInterrupt && fifoCount < packetSize) {
    new_pid();
  }
  // reset interrupt flag and get INT_STATUS byte
  mpuInterrupt = false;
  mpuIntStatus = mpu.getIntStatus();</p><p>  // get current FIFO count
  fifoCount = mpu.getFIFOCount();</p><p>  // 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!"));</p><p>    // 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();</p><p>    // read a packet from FIFO
    mpu.getFIFOBytes(fifoBuffer, packetSize);</p><p>    // track FIFO count here in case there is > 1 packet available
    // (this lets us immediately read more without waiting for an interrupt)
    fifoCount -= packetSize;</p><p>    mpu.dmpGetQuaternion(&q, fifoBuffer); //get value for q
    mpu.dmpGetGravity(&gravity, &q); //get value for gravity
    mpu.dmpGetYawPitchRoll(ypr, &q, &gravity); //get value for ypr</p><p>    input = ypr[1] * 180 / M_PI + 180;
    yinput = ypr[0] * 180 / M_PI;
  }
}</p><p>void new_pid() {
  //Compute error
  pid.Compute();
  rot.Compute();
  // Convert PID output to motor control
  MotorAspeed = compensate_slack(youtput, output, 1);
  MotorBspeed = compensate_slack(youtput, output, 0);
  motorspeed(MotorAspeed, MotorBspeed);            //change speed
}
//Fast digitalWrite is implemented</p><p>void Bt_control() {
  if (blue.available()) {
    content = blue.read();
    if (content == 'F')
      setpoint = originalSetpoint - d_speed;//Serial.println(setpoint);}            //forward
    else if (content == 'B')
      setpoint = originalSetpoint + d_speed;//Serial.println(setpoint);}            //backward
    else if (content == 'L')
      ysetpoint = constrain((ysetpoint + yoriginalSetpoint - d_dir), -180, 180); //Serial.println(ysetpoint);}      //left
    else if (content == 'R')
      ysetpoint = constrain(ysetpoint + yoriginalSetpoint + d_dir, -180, 180); //Serial.println(ysetpoint);}        //right
    else if (content == 'S') {
      setpoint = originalSetpoint;
    }
  }
  else content = 'P';
}</p><p>void initmot() {
  //Initialise the Motor outpu pins
  pinMode (IN4, OUTPUT);
  pinMode (IN3, OUTPUT);
  pinMode (IN2, OUTPUT);
  pinMode (IN1, OUTPUT);</p><p>  //By default turn off both the motor
  analogWrite(IN4, LOW);
  analogWrite(IN3, LOW);
  analogWrite(IN2, LOW);
  analogWrite(IN1, LOW);
}</p><p>double compensate_slack(double yOutput, double Output, bool A) {
  // Compensate for DC motor non-linear "dead" zone around 0 where small values don't result in movement
  //yOutput is for left,right control
  if (A)
  {
    if (Output >= 0)
      Output = Output + MOTORSLACK_A - yOutput;
    if (Output < 0)
      Output = Output - MOTORSLACK_A - yOutput;
  }
  else
  {
    if (Output >= 0)
      Output = Output + MOTORSLACK_B + yOutput;
    if (Output < 0)
      Output = Output - MOTORSLACK_B + yOutput;
  }
  Output = constrain(Output, BALANCE_PID_MIN, BALANCE_PID_MAX);
  return Output;
}</p><p>void motorspeed(int MotorAspeed, int MotorBspeed) {</p><p>  // Motor A control
  if (MotorAspeed >= 0) {
    analogWrite(IN1, abs(MotorAspeed));
    digitalWrite(IN2, LOW);
  }
  else {
    digitalWrite(IN1, LOW);
    analogWrite(IN2, abs(MotorAspeed));
  }</p><p>  // Motor B control
  if (MotorBspeed >= 0) {
    analogWrite(IN3, abs(MotorBspeed));
    digitalWrite(IN4, LOW);
  }
  else {
    digitalWrite(IN3, LOW);
    analogWrite(IN4, abs(MotorBspeed));
  }
}
void printval()
{
  Serial.print(yinput); Serial.print("\t");
  Serial.print(yoriginalSetpoint); Serial.print("\t");
  Serial.print(ysetpoint); Serial.print("\t");
  Serial.print(youtput); Serial.print("\t"); Serial.print("\t");
  Serial.print(input); Serial.print("\t");
  Serial.print(originalSetpoint); Serial.print("\t");
  Serial.print(setpoint); Serial.print("\t");
  Serial.print(output); Serial.print("\t"); Serial.print("\t");
  Serial.print(MotorAspeed); Serial.print("\t");
  Serial.print(MotorBspeed); Serial.print("\t"); Serial.print(content); Serial.println("\t");
}</p>

Description:

I used the MIT APP INVENTOR to create an application which uses bluetooth to send commands to the self balancing robot, i did create for command forward backward right and left , you can add other command if you want.

Here is a link to download the app:

http://www.mediafire.com/file/ffrkmu9oerynsv7/Moun...

Description:

YOU MIGHT ALSO LIKE