Debreczeni Tamas
Published © GPL3+

Arduino Self-Balancing Robot

Self-balancing robot with two ultrasonic proximity sensors and nRF24 communication + remote.

IntermediateShowcase (no instructions)24 hours24,510

Things used in this project

Story

Read more

Custom parts and enclosures

Robot

Schematics

Arduino NRF24 remote

Robot

Code

Self balancing robot

Arduino
#include <PID_v1.h>                                   //PID
#include <LMotorController.h>                         //Motor driver L298N
#include "I2Cdev.h"                                   //I2C communication
#include "MPU6050_6Axis_MotionApps20.h"               //Gyroscope
#include <SPI.h>                                      //SPI communication for NRF24
#include <nRF24L01.h>                                 //NRF24
#include <RF24.h>                                     //NRF24     
#include <Ultrasonic.h>                               //Ultrasonic sensor

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

# define MIN_ABS_SPEED 30                             //Minimum motor speed (PWM)
                                                
//Motor driver pins
int ENA = 5;
int IN1 = 6;
int IN2 = 7;
int IN3 = 8;
int IN4 = 9;
int ENB = 10;

MPU6050 mpu;

// MPU control/status 
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 
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 parameters
double originalSetpoint = 181.80;
double setpoint = originalSetpoint;
double movingAngleOffset = 0.1;
double input, output;

//
double Kp = 60;
double Kd = 2.2;
double Ki = 270;
PID pid( & input, & output, & setpoint, Kp, Ki, Kd, DIRECT);

//To equalize differences between motors
double motorSpeedFactorLeft = 0.65;
double motorSpeedFactorRight = 0.50;
double OriginalmotorSpeedFactorLeft = 0.65;
double OriginalmotorSpeedFactorRight = 0.50;


LMotorController motorController(ENA, IN1, IN2, ENB, IN3, IN4, motorSpeedFactorLeft, motorSpeedFactorRight);

volatile bool mpuInterrupt = false; // indicates whether MPU interrupt pin has gone high


RF24 radio(3, 4); // CE, CSN
const byte address[6] = "06720"; //NRF adress
unsigned long lastRecvTime = 0;  //Used to check for delays

//Structure of received data by radio
struct data {
  double left;
  double right;
  double dir;
  double inputValue;
  boolean modify;
  short inputMode;
  boolean ultrasonicSensorOn;
};

data receive_data;

Ultrasonic ultraleft(A2, A3);   // (Trig PIN,Echo PIN)
Ultrasonic ultraright(A0, A1);  // (Trig PIN,Echo PIN)

int distanceCm;
int distanceCm2;;

int loopNumber = 0;

void dmpDataReady() {
  mpuInterrupt = true;
}

//Reset values in case of radio signal loss
void reset_the_Data()          
{
  receive_data.left = 0;
  receive_data.right = 0;
  receive_data.dir = 0;
  receive_data.ultrasonicSensorOn = true;
}

//Read data received by radio
void receive_the_data() 
{
  while (radio.available()) {
    radio.read( & receive_data, sizeof(data));
    lastRecvTime = millis();
  }
}

//Select PID parameter that changes
void setInputValue(double inpVal, short inpMode) {
  switch (inpMode) {
      case 0:
        originalSetpoint = inpVal;
        break;
      case 1:
        Kp = inpVal;
        break;
      case 2:
        Kd = inpVal;
        break;
      case 3:
        Ki = inpVal;
        break;
  }
}

void setup() {
  Serial.begin(9600); // open the serial port at 9600 bps:    

  // 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); 

  // 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(")"));
  }

  radio.begin();
  radio.setAutoAck(false);
  radio.openReadingPipe(0, address);
  radio.setPALevel(RF24_PA_MIN);
  radio.setDataRate(RF24_250KBPS);
  radio.startListening();

}

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;
  }

  receive_the_data();

  unsigned long now = millis();
  if (now - lastRecvTime > 1000) { //If the delay is greater, reset the data
    reset_the_Data();
  }

  //Direction control with data from remote control
  setpoint = originalSetpoint + receive_data.dir;
  motorSpeedFactorRight = OriginalmotorSpeedFactorRight + receive_data.right;
  motorSpeedFactorLeft = OriginalmotorSpeedFactorLeft + receive_data.left;
 

  if (receive_data.modify) {
    setInputValue(receive_data.inputValue, receive_data.inputMode);
    PID pid2( & input, & output, & setpoint, Kp, Ki, Kd, DIRECT);
    pid2.SetMode(AUTOMATIC);
    pid2.SetSampleTime(10);
    pid2.SetOutputLimits(-255, 255);
    pid = pid2;
  }

  if (input < 150 || input > 210) {
    digitalWrite(ENA, LOW);
    digitalWrite(ENB, LOW);
  }

  //Robot handling with ultrasonic sensors (Setpoint)
  if (loopNumber == 2) {
    if (receive_data.ultrasonicSensorOn && ultraleft.Ranging(CM) < 30 && ultraleft.Ranging(CM) != 0) {
      setpoint = originalSetpoint - 4;  
    } else {
      if (receive_data.ultrasonicSensorOn && ultraright.Ranging(CM) < 30 && ultraright.Ranging(CM) != 0) {
        setpoint = originalSetpoint + 4; 
      }
    }
    loopNumber = 0;
  }
  loopNumber++; 
      
}

Arduino NRF24 remote

Arduino
//Remote Transmitter
#include <SPI.h>
#include <nRF24L01.h>
#include <RF24.h>

//LED Display
#include <Wire.h>
#include <Adafruit_GFX.h>
#include <Adafruit_SSD1306.h>

#define SCREEN_WIDTH 128 // OLED display width, in pixels
#define SCREEN_HEIGHT 64 // OLED display height, in pixels

# define L_AXIS A0 // Left Y Axis Port DIR
# define R_AXIS A3 // Right Y Axis Port
# define VALUE A7  // Left Y Axis Port DIR
# define MODIFY 9  // Right Y Axis Port
# define MODE1 2   // Right Y Axis Port
# define MODE2 3   // Right Y Axis Port
# define US_ON 6   // Ultrasonic sensor Port

//LED Display
//Declaration for an SSD1306 display connected to I2C (SDA, SCL pins)
Adafruit_SSD1306 display(SCREEN_WIDTH, SCREEN_HEIGHT, & Wire, -1);

float value;
float voltage;

double Os = 182.15;
double Kp = 60.0;
double Kd = 2.2;
double Ki = 270;

boolean ultrasonicSensorOn = true;
int prevButtonState = LOW;
int buttonState = LOW;

struct data {
  double left;
  double right;
  double dir;
  double value;
  boolean modify;
  short mode;
  boolean ultrasonicSensorOn;
};
data send_data;

RF24 radio(7, 8); // CE, CSN
const byte address[6] = "06720"; //NRF Address
void setup() {

  Serial.begin(9600);

  pinMode(MODE1, INPUT_PULLUP);
  pinMode(MODE2, INPUT_PULLUP);
  pinMode(VALUE, INPUT);
  pinMode(MODIFY, INPUT);
  pinMode(US_ON, INPUT);

  Wire.begin();
  display.begin(SSD1306_SWITCHCAPVCC, 0x3C);

  radio.begin();
  radio.setAutoAck(false);
  radio.openWritingPipe(address);
  radio.setPALevel(RF24_PA_HIGH);
  radio.setDataRate(RF24_250KBPS);
  radio.stopListening();
}

float mapFloat(float x, float in_min, float in_max, float out_min, float out_max) {
  return (x - in_min) * (out_max - out_min) / (in_max - in_min) + out_min;
}

int getMode(int mode1, int mode2) {
  if (mode1 == HIGH && mode2 == HIGH)
    return 0;
  if (mode1 == HIGH && mode2 == LOW)
    return 1;
  if (mode1 == LOW && mode2 == HIGH)
    return 2;
  if (mode1 == LOW && mode2 == LOW)
    return 3;

}

char * getModeName(int mode) {
  switch (mode) {
  case 0:
    return "Os";
  case 1:
    return "Kp";
  case 2:
    return "Kd";
  case 3:
    return "Ki";
  }
}

float getValue(int mode, int value) {
  switch (mode) {
  case 0:
    return mapFloat(value, 1023, 0, 170.0, 190.0);
  case 1:
    return mapFloat(value, 1023, 0, 0.0, 100.0);
  case 2:
    return mapFloat(value, 1023, 0, 0.0, 5.0);
  case 3:
    return mapFloat(value, 1023, 0, 0.0, 500.0);
  }
}

void setOriginalValue(int mode, double value) {
  switch (mode) {
  case 0:
    Os = value;
    break;
  case 1:
    Kp = value;
    break;
  case 2:
    Kd = value;
    break;
  case 3:
    Ki = value;
    break;
  }
}

void loop() {

  int readLaxis = analogRead(L_AXIS);
  int readRaxis = analogRead(R_AXIS);
  int readValue = analogRead(VALUE);
  int readModify = digitalRead(MODIFY);
  int mode1 = digitalRead(MODE1);
  int mode2 = digitalRead(MODE2);
  buttonState = digitalRead(US_ON);

  send_data.dir = readLaxis > 497 && readLaxis < 517 ? 0 : mapFloat(readLaxis, 0, 1023, -2.00, 2.00); //A ?0: (ternary valami roviditett if
  send_data.right = readRaxis > 492 && readRaxis < 512 ? 0 : mapFloat(readRaxis, 0, 1023, -0.50, 0.50);
  send_data.left = readRaxis > 492 && readRaxis < 512 ? 0 : mapFloat(readRaxis, 0, 1023, 0.50, -0.50);
  send_data.value = getValue(getMode(mode1, mode2), readValue);
  send_data.modify = readModify == HIGH;
  send_data.mode = getMode(mode1, mode2);

  //  Serial.print(send_data.right);
  //  Serial.print(" ");
  //  Serial.println(send_data.left);
  //  Serial.println(digitalRead(MODIFY));
  //  Serial.println(digitalRead(US_ON));

  if (send_data.modify) {
    setOriginalValue(send_data.mode, send_data.value);
  }

  if (prevButtonState != buttonState) {
    if (buttonState == HIGH) {
      ultrasonicSensorOn = !ultrasonicSensorOn;
      send_data.ultrasonicSensorOn = ultrasonicSensorOn;
    }
  }

  prevButtonState = buttonState;

  radio.write( & send_data, sizeof(data));

  value = analogRead(A6);
  voltage = ((5 * value) / 1023) * 4.103354632587859;

  display.clearDisplay();
  display.setTextColor(WHITE);
  display.setTextSize(1);
  display.setCursor(0, 0);

  display.print("Dir: ");
  display.println(send_data.dir);
  display.print("Os: ");
  display.print(Os);
  display.print(" Kp: ");
  display.print(Kp);
  display.print(" Kd: ");
  display.print(Kd);
  display.print("   Ki: ");
  display.println(Ki);
  display.print("\n");
  display.print(getModeName(send_data.mode));
  display.print(": ");
  display.println(send_data.value);
  display.println(ultrasonicSensorOn);
  display.print("\n");
  display.print("Voltage: ");
  display.print(voltage);
  display.print("V");

  display.display();

}

Credits

Debreczeni Tamas

Debreczeni Tamas

6 projects • 33 followers

Comments