Tutorial: Using VL53L0X ToF Sensor with Motors for Obstacle Detection and Avoidance

Introduction

In this tutorial, you will learn how to use the VL53L0X Time-of-Flight (ToF) sensor to detect obstacles and make a robot avoid them by turning 90 degrees when an obstacle is detected. The robot will use two DC motors for movement.

Components Needed

  • Arduino board (e.g., Uno, Nano)
  • VL53L0X ToF sensor
  • 2 DC motors
  • L298N motor driver or any suitable motor driver
  • Breadboard and jumper wires
  • Power supply for the motors

Circuit Diagram

Connect the components as follows:

VL53L0X ToF Sensor

  • VCC to 5V (or 3.3V depending on your sensor)
  • GND to GND
  • SDA to A4 (or the SDA pin on your Arduino)
  • SCL to A5 (or the SCL pin on your Arduino)

Motor Driver (L298N)

  • ENA to PWM pin 3
  • IN1 to digital pin 4
  • IN2 to digital pin 5
  • ENB to PWM pin 9
  • IN3 to digital pin 8
  • IN4 to digital pin 7
  • Motor A connections to one motor
  • Motor B connections to the other motor
  • Connect VCC and GND of the motor driver to the power supply (make sure the GND is common with the Arduino)

alt text

Code Explanation

Here's the code we'll be using:

#include <Wire.h>
#include <VL53L0X.h>

// Motor A connections
#define enA 3
#define in1 4
#define in2 5

// Motor B connections
#define enB 9
#define in3 8
#define in4 7

VL53L0X sensor;

void setup() {
  Serial.begin(9600);
  Wire.begin();

  // Initialize ToF sensor
  sensor.init();
  sensor.setTimeout(500);
  sensor.startContinuous();

  // Set all the motor control pins to outputs
  pinMode(enA, OUTPUT);
  pinMode(in1, OUTPUT);
  pinMode(in2, OUTPUT);
  pinMode(enB, OUTPUT);
  pinMode(in3, OUTPUT);
  pinMode(in4, OUTPUT);

  // Turn off motors - Initial state
  stopMotors();
}

void loop() {
  // Read distance from sensor
  uint16_t distance = sensor.readRangeContinuousMillimeters();

  // Print distance to serial monitor
  Serial.println(distance);

  // If an obstacle is detected within 100 mm
  if (distance < 100) {
    stopMotors();
    delay(500); // Short delay before turning

    // Turn 90 degrees
    turnRight();
    delay(500); // Adjust this delay to achieve a 90-degree turn

    stopMotors();
    delay(500); // Short delay after turning
  } else {
    // Move forward if no obstacle is detected
    moveForward();
  }
}

void moveForward() {
  // Motor A forward
  digitalWrite(in1, HIGH);
  digitalWrite(in2, LOW);

  // Motor B forward
  digitalWrite(in3, HIGH);
  digitalWrite(in4, LOW);

  // Set speed
  analogWrite(enA, 255); // Max speed for Motor A
  analogWrite(enB, 255); // Max speed for Motor B
}

void stopMotors() {
  // Turn off motors
  digitalWrite(in1, LOW);
  digitalWrite(in2, LOW);
  digitalWrite(in3, LOW);
  digitalWrite(in4, LOW);
}

void turnRight() {
  // Motor A forward
  digitalWrite(in1, HIGH);
  digitalWrite(in2, LOW);

  // Motor B backward
  digitalWrite(in3, LOW);
  digitalWrite(in4, HIGH);

  // Set speed
  analogWrite(enA, 255); // Max speed for Motor A
  analogWrite(enB, 255); // Max speed for Motor B
}

Steps

  1. Connect the Hardware:
  2. Follow the circuit diagram to connect the VL53L0X sensor, motors, and motor driver to the Arduino.

  3. Upload the Code:

  4. Open the Arduino IDE.
  5. Copy and paste the provided code into the IDE.
  6. Select the correct board and port from the Tools menu.
  7. Upload the code to your Arduino board.

  8. Test the Robot:

  9. Place your robot in an open area.
  10. Power it on.
  11. The robot should move forward until it detects an obstacle within 100 mm.
  12. When an obstacle is detected, the robot will stop, turn 90 degrees to the right, and then continue moving forward.

Adjustments

  • Turning Delay:
  • Adjust the delay(500); in the turnRight() function to fine-tune the turning angle. Increase the delay if the robot turns less than 90 degrees or decrease it if it turns more.

  • Obstacle Distance:

  • Change the if (distance < 100) condition to adjust the detection range. For example, use if (distance < 200) to detect obstacles within 200 mm.

Troubleshooting

  • Sensor Not Detected:
  • Ensure the VL53L0X sensor is properly connected and powered.
  • Check the I2C connections (SDA and SCL).

  • Motors Not Working:

  • Verify the motor driver connections and power supply.
  • Check the motor driver enable pins (ENA and ENB).

  • Unexpected Behavior:

  • Make sure the code is correctly uploaded.
  • Use the Serial Monitor to debug distance readings from the sensor.

Conclusion

You have successfully built a simple obstacle-avoiding robot using the VL53L0X ToF sensor and two DC motors. This basic framework can be expanded to create more complex robotics projects by adding additional sensors, functionality, and refining the control logic.


Additional Tasks

Task 1: Fine-Tuning the Turning Angle - Description: Adjust the delay in the turnRight() function to achieve a perfect 90-degree turn. - Hint:

Click to expand hint Experiment with different delay values in the `turnRight()` function. For example, try `delay(400);` or `delay(600);` and observe the turning angle. Adjust the delay until the robot turns exactly 90 degrees.

Task 2: Adjusting the Obstacle Detection Range - Description: Modify the distance threshold for obstacle detection to make the robot stop at a different distance from obstacles. - Hint:

Click to expand hint Change the condition `if (distance < 100)` to `if (distance < 200)` to detect obstacles within 200 mm instead of 100 mm. You can set any value depending on your requirement.

Task 3: Implementing Left Turn as an Alternative - Description: Modify the code to make the robot turn left instead of right when an obstacle is detected. - Hint:

Click to expand hint Create a new function `turnLeft()` similar to `turnRight()`, but swap the motor directions. For example:
void turnLeft() {
  // Motor A backward
  digitalWrite(in1, LOW);
  digitalWrite(in2, HIGH);

  // Motor B forward
  digitalWrite(in3, HIGH);
  digitalWrite(in4, LOW);

  // Set speed
  analogWrite(enA, 255); // Max speed for Motor A
  analogWrite(enB, 255); // Max speed for Motor B
}
Replace `turnRight();` with `turnLeft();` in the `loop()`.

Task 4: Implementing a Three-Point Turn - Description: Make the robot perform a three-point turn when an obstacle is detected. - Hint:

Click to expand hint Implement a three-point turn by combining forward, backward, and turning movements. For example:
void threePointTurn() {
  moveBackward();
  delay(1000); // Move backward for 1 second
  stopMotors();
  delay(500); // Short delay

  turnRight();
  delay(500); // Turn right for 0.5 second
  stopMotors();
  delay(500); // Short delay

  moveForward();
  delay(1000); // Move forward for 1 second
  stopMotors();
  delay(500); // Short delay

  turnLeft();
  delay(500); // Turn left for 0.5 second
  stopMotors();
}
Call `threePointTurn();` in the `loop()` when an obstacle is detected.

Task 5: Adding LED Strip with FastLED - Description: Connect an 8-LED WS2812B strip to the Arduino and use the FastLED library to light up the strip when an obstacle is detected. - Hint:

Click to expand hint Install the FastLED library from the Arduino Library Manager. Connect the data pin of the WS2812B strip to a digital pin on the Arduino (e.g., pin 6). Use the following code snippet to control the LED strip:
#include <FastLED.h>

#define LED_PIN     6
#define NUM_LEDS    8

CRGB leds[NUM_LEDS];

void setup() {
  FastLED.addLeds<WS2812, LED_PIN, GRB>(leds, NUM_LEDS).setCorrection(TypicalLEDStrip);
  FastLED.setBrightness(50);
  // Other setup code...
}

void loop() {
  uint16_t distance = sensor.readRangeContinuousMillimeters();
  Serial.println(distance);

  if (distance < 100) {
    stopMotors();
    delay(500);

    turnRight();
    delay(500);

    stopMotors();
    delay(500);

    // Light up the LED strip when an obstacle is detected
    for (int i = 0; i < NUM_LEDS; i++) {
      leds[i] = CRGB::Red;
    }
    FastLED.show();
  } else {
    moveForward();

    // Turn off the LED strip when no obstacle is detected
    for (int i = 0; i < NUM_LEDS; i++) {
      leds[i] = CRGB::Black;
    }
    FastLED.show();
  }
}

// Other functions (moveForward, stopMotors, turnRight, etc.) remain the same...

Task 6: Adding MPU6050 for Movement Detection - Description: Connect an MPU6050 to the Arduino to detect movement in the Z direction and stop the motors when the robot is picked up. - Hint:

Click to expand hint Install the MPU6050 library from the Arduino Library Manager. Connect the MPU6050 as follows: - VCC to 5V - GND to GND - SDA to A4 (or the SDA pin on your Arduino) - SCL to A5 (or the SCL pin on your Arduino) Use the following code snippet to integrate the MPU6050:
#include <Wire.h>
#include <VL53L0X.h>
#include <FastLED.h>
#include <MPU6050.h>

// Motor A connections
#define enA 3
#define in1 4
#define in2 5

// Motor B connections
#define enB 9
#define in3 8
#define in4 7

// LED strip connections
#define LED_PIN 6
#define NUM_LEDS 8

CRGB leds[NUM_LEDS];
VL53L0X sensor;
MPU6050 mpu;

void setup() {
  Serial.begin(9600);
  Wire.begin();

  // Initialize ToF sensor
  sensor.init();
  sensor.setTimeout(500);
  sensor.startContinuous();

  // Initialize MPU6050
  mpu.initialize();
  if (!mpu.testConnection()) {
    Serial.println("MPU6050 connection failed");
    while (1);
  }

  // Initialize FastLED
  FastLED.addLeds<WS2812, LED_PIN, GRB>(leds, NUM_LEDS).setCorrection(TypicalLEDStrip);
  FastLED.setBrightness(50);

  // Set all the motor control pins to outputs
  pinMode(enA, OUTPUT);
  pinMode(in1, OUTPUT);
  pinMode(in2, OUTPUT);
  pinMode(enB, OUTPUT);
  pinMode(in3, OUTPUT);
  pinMode(in4, OUTPUT);

  // Turn off motors - Initial state
  stopMotors();
}

void loop() {
  uint16_t distance = sensor.readRangeContinuousMillimeters();
  Serial.println(distance);

  // Read Z-axis acceleration
  int16_t az = mpu.getAccelerationZ();

  if (distance < 100) {
    stopMotors();
    delay(500);

    turnRight();
    delay(500);

    stopMotors();
    delay(500);

    // Light up the LED strip when an obstacle is detected
    for (int i = 0; i < NUM_LEDS; i++) {
      leds[i] = CRGB::Red;
    }
    FastLED.show();
  } else if (az > 15000 || az < -15000) {  // Adjust threshold as needed
    stopMotors();

    // Light up the LED strip in blue when picked up
    for (int i = 0; i < NUM_LEDS; i++) {
      leds[i] = CRGB::Blue;
    }
    FastLED.show();
  } else {
    moveForward();

    // Turn off the LED strip when no obstacle is detected
    for (int i = 0; i < NUM_LEDS; i++) {
      leds[i] = CRGB::Black;
    }
    FastLED.show();
  }
}

void moveForward() {
  // Motor A forward
  digitalWrite(in1, HIGH);
  digitalWrite(in2, LOW);

  // Motor B forward
  digitalWrite(in3, HIGH);
  digitalWrite(in4, LOW);

  // Set speed
  analogWrite(enA, 255); // Max speed for Motor A
  analogWrite(enB, 255); // Max speed for Motor B
}

void stopMotors() {
  // Turn off motors
  digitalWrite(in1, LOW);
  digitalWrite(in2, LOW);
  digitalWrite(in3, LOW);
  digitalWrite(in4, LOW);
}

void turnRight() {
  // Motor A forward
  digitalWrite(in1, HIGH);
  digitalWrite(in2, LOW);

  // Motor B backward
  digitalWrite(in3, LOW);
  digitalWrite(in4, HIGH);

  // Set speed
  analogWrite(enA, 255); // Max speed for Motor A
  analogWrite(enB, 255); // Max speed for Motor B
}
This code will stop the motors and change the LED strip to blue when the robot is picked up (i.e., significant movement detected in the Z direction).

By completing these additional tasks, you can enhance your robot's functionality and gain more experience with Arduino programming and sensor integration. Each task builds on the basic framework provided, allowing you to create a more versatile and interactive robot.