Human Following Robot Using Arduino and Ultrasonic Sensor

Submitted by Gourav Tak on

Working of Human Following Robot Using Arduino

In recent years, robotics has witnessed significant advancements, enabling the creation of intelligent machines that can interact with the environment. One exciting application of robotics is the development of human-following robots. These robots can track and follow a person autonomously, making them useful in various scenarios like assistance in crowded areas, navigation support, or even as companions. In this article, we will explore in detail how to build a human following robot using Arduino and three ultrasonic sensors, complete with circuit diagrams and working code. Also, check all the Arduino-based Robotics projects by following the link.

The working of a human following robot using Arduino code and three ultrasonic sensors is an interesting project. What makes this project particularly interesting is the use of not just one, but three ultrasonic sensors. This adds a new dimension to the experience, as we typically see humans following a robot built with one ultrasonic, two IR, and one servo motor.  This servo motor has no role in the operation and also adds unnecessary complications. So I removed this servo and the IR sensors and used 3 ultrasonic sensors. With ultrasonic sensors, you can measure distance and use that information to navigate and follow a human target. Here’s a general outline of the steps involved in creating such a robot.

 

 

Components Needed for Human Following Robot Using Arduino

  • Arduino UNO board ×1

  • Ultrasonic sensor ×3

  • L298N motor driver ×1

  • Robot chassis

  • BO motors ×2

  • Wheels ×2

  • Li-ion battery 3.7V ×2

  • Battery holder ×1

  • Breadboard

  • Ultrasonic sensor holder ×3

  • Switch and jumper wires

Human Following Robot Using Arduino Circuit Diagram

Here is the schematic diagram of a Human-following robot circuit.

Arduino Human Following Robot Circuit Diagram

This design incorporates three ultrasonic sensors, allowing distance measurements in three directions front, right, and left. These sensors are connected to the Arduino board through their respective digital pins. Additionally, the circuit includes two DC motors for movement, which are connected to an L298N motor driver module. The motor driver module is, in turn, connected to the Arduino board using its corresponding digital pins. To power the entire setup, two 3.7V li-ion cells are employed, which are connected to the motor driver module via a switch.

Overall, this circuit diagram showcases the essential components and connections necessary for the Human-following robot to operate effectively.

arduino human following robot circuit

Circuit Connection:

Arduino and HC-SR04 Ultrasonic Sensor Module:

HC-SR04 Ultrasonic sensor Module

  • Connect the VCC pin of each ultrasonic sensor to the 5V pin on the Arduino board.

  • Connect the GND pin of each ultrasonic sensor to the GND pin on the Arduino board.

  • Connect the trigger pin (TRIG) of each ultrasonic sensor to separate digital pins (2,4, and 6) on the Arduino board.

  • Connect the echo pin (ECHO) of each ultrasonic to separate digital pins (3,5, and 7) on the Arduino board.

Arduino and Motor Driver Module:

  • Connect the digital output pins of the Arduino (digital pins 8, 9, 10, and 11) to the appropriate input pins (IN1, IN2, IN3, and IN4) on the motor driver module.

  • Connect the ENA and ENB pins of the motor driver module to the onboard High state pin with the help of a female header.

  • Connect the OUT1, OUT2, OUT3, and OUT4 pins of the motor driver module to the appropriate terminals of the motors.

  • Connect the VCC (+5V) and GND pins of the motor driver module to the appropriate power (Vin) and ground (GND) connections on the Arduino.

Power Supply:

  • Connect the positive terminal of the power supply to the +12V input of the motor driver module.

  • Connect the negative terminal of the power supply to the GND pin of the motor driver module.

  • Connect the GND pin of the Arduino to the GND pin of the motor driver module.

Human Following Robot Using Arduino Code

Here is a simple 3 Ultrasonic sensor-based Human following robot using Arduino Uno code that you can use for your project.

Ultrsonic Sensors on Robot

This code reads the distances from three ultrasonic sensors (‘frontDistance’, ‘leftDistance’, and ‘rightDistance’). It then compares these distances to determine the sensor with the smallest distance. If the smallest distance is below the threshold, it moves the car accordingly using the appropriate motor control function (‘moveForward()’, ‘turnLeft()’, ‘turnRight()’). If none of the distances are below the threshold, it stops the motor using ‘stop()’.

In this section, we define the pin connections for the ultrasonic sensors and motor control. The S1Trig, S2Trig, and S3Trig, variables represent the trigger pins of the three ultrasonic sensors, while S1Echo, S2Echo, and S3Echo, represent their respective echo pins.

The LEFT_MOTOR_PIN1, LEFT_MOTOR_PIN2, RIGHT_MOTOR_PIN1, and RIGHT_MOTOR_PIN2 variables define the pins for controlling the motors.

The MAX_DISTANCE and MIN_DISTANCE_BACK variables set the thresholds for obstacle detection.

// Ultrasonic sensor pins
#define S1Trig 2
#define S2Trig 4
#define S3Trig 6
#define S1Echo 3
#define S2Echo 5
#define S3Echo 7
// Motor control pins
#define LEFT_MOTOR_PIN1 8
#define LEFT_MOTOR_PIN2 9
#define RIGHT_MOTOR_PIN1 10
#define RIGHT_MOTOR_PIN2 11
// Distance thresholds for obstacle detection
#define MAX_DISTANCE 40
#define MIN_DISTANCE_BACK 5

Make sure to adjust the values of ‘MIN_DISTANCE_BACK’ and ‘MAX_DISTANCE’ according to your specific requirements and the characteristics of your robot.

The suitable values for ‘MIN_DISTANCE_BACK’ and ‘MAX_DISTANCE’ depend on the specific requirements and characteristics of your human-following robot. You will need to consider factors such as the speed of your robot, the response time of the sensors, and the desired safety margin

Here are some general guidelines to help you choose suitable values.

MIN_DISTANCE_BACK’ This value represents the distance at which the car should come to a stop when an obstacle or hand is detected directly in front. It should be set to a distance that allows the car to back safely without colliding with the obstacle or hand. A typical value could be around 5-10 cm.

MAX_DISTANCE’ This value represents the maximum distance at which the car considers the path ahead to be clear and can continue moving forward. It should be set to a distance that provides enough room for the car to move without colliding with any obstacles or hands. If your hand and obstacles are going out of this range, the robot should be stop. A typical value could be around 30-50 cm.

These values are just suggestions, and you may need to adjust them based on the specific characteristics of your robot and the environment in which it operates.

These lines set the motor speed limits. ‘MAX_SPEED’ denotes the upper limit for motor speed, while ‘MIN_SPEED’ is a lower value used for a slight left bias. The speed values are typically within the range of 0 to 255, and can be adjusted to suit our specific requirements.

// Maximum and minimum motor speeds
#define MAX_SPEED 150
#define MIN_SPEED 75

The ‘setup()’ function is called once at the start of the program. In the setup() function, we set the motor control pins (LEFT_MOTOR_PIN1, LEFT_MOTOR_PIN2, RIGHT_MOTOR_PIN1, RIGHT_MOTOR_PIN2) as output pins using ‘pinMode()’ . We also set the trigger pins (S1Trig, S2Trig, S3Trig) of the ultrasonic sensors as output pins and the echo pins (S1Echo, S2Echo, S3Echo) as input pins. Lastly, we initialize the serial communication at a baud rate of 9600 for debugging purposes.

void setup() {
  // Set motor control pins as outputs
  pinMode(LEFT_MOTOR_PIN1, OUTPUT);
  pinMode(LEFT_MOTOR_PIN2, OUTPUT);
  pinMode(RIGHT_MOTOR_PIN1, OUTPUT);
  pinMode(RIGHT_MOTOR_PIN2, OUTPUT);
  //Set the Trig pins as output pins
  pinMode(S1Trig, OUTPUT);
  pinMode(S2Trig, OUTPUT);
  pinMode(S3Trig, OUTPUT);
  //Set the Echo pins as input pins
  pinMode(S1Echo, INPUT);
  pinMode(S2Echo, INPUT);
  pinMode(S3Echo, INPUT);
  // Initialize the serial communication for debugging
  Serial.begin(9600);
}

This block of code consists of three functions (‘sensorOne()’, ‘sensorTwo()’, ‘sensorThree()’) responsible for measuring the distance using ultrasonic sensors.

The ‘sensorOne()’ function measures the distance using the first ultrasonic sensor. It's important to note that the conversion of the pulse duration to distance is based on the assumption that the speed of sound is approximately 343 meters per second. Dividing by 29 and halving the result provides an approximate conversion from microseconds to centimeters.

The ‘sensorTwo()’ and ‘sensorThree()’ functions work similarly, but for the second and third ultrasonic sensors, respectively.

// Function to measure the distance using an ultrasonic sensor
int sensorOne() {
  //pulse output
  digitalWrite(S1Trig, LOW);
  delayMicroseconds(2);
  digitalWrite(S1Trig, HIGH);
  delayMicroseconds(10);
  digitalWrite(S1Trig, LOW);
  long t = pulseIn(S1Echo, HIGH);//Get the pulse
  int cm = t / 29 / 2; //Convert time to the distance
  return cm; // Return the values from the sensor
}
//Get the sensor values
int sensorTwo() {
  //pulse output
  digitalWrite(S2Trig, LOW);
  delayMicroseconds(2);
  digitalWrite(S2Trig, HIGH);
  delayMicroseconds(10);
  digitalWrite(S2Trig, LOW);
  long t = pulseIn(S2Echo, HIGH);//Get the pulse
  int cm = t / 29 / 2; //Convert time to the distance
  return cm; // Return the values from the sensor
}
//Get the sensor values
int sensorThree() {
  //pulse output
  digitalWrite(S3Trig, LOW);
  delayMicroseconds(2);
  digitalWrite(S3Trig, HIGH);
  delayMicroseconds(10);
  digitalWrite(S3Trig, LOW);
  long t = pulseIn(S3Echo, HIGH);//Get the pulse
  int cm = t / 29 / 2; //Convert time to the distance
  return cm; // Return the values from the sensor
}

In this section, the ‘loop()’ function begins by calling the ‘sensorOne()’, ‘sensorTwo()’, and ‘sensorThree()’ functions to measure the distances from the ultrasonic sensors. The distances are then stored in the variables ‘frontDistance’, ‘leftDistance’, and ‘rightDistance’.

Next, the code utilizes the ‘Serial’ object to print the distance values to the serial monitor for debugging and monitoring purposes.

void loop() {
  int frontDistance = sensorOne();
  int leftDistance = sensorTwo();
  int rightDistance = sensorThree();
  Serial.print("Front: ");
  Serial.print(frontDistance);
  Serial.print(" cm, Left: ");
  Serial.print(leftDistance);
  Serial.print(" cm, Right: ");
  Serial.print(rightDistance);
  Serial.println(" cm");

In this section of code condition checks if the front distance is less than a threshold value ‘MIN_DISTANCE_BACK’ that indicates a very low distance. If this condition is true, it means that the front distance is very low, and the robot should move backward to avoid a collision. In this case, the ‘moveBackward()’ function is called.

if (frontDistance < MIN_DISTANCE_BACK) {
    moveBackward();
    Serial.println("backward");

If the previous condition is false, this condition is checked. if the front distance is less than the left distance, less than the right distance, and less than the ‘MAX_DISTANCE’ threshold. If this condition is true, it means that the front distance is the smallest among the three distances, and it is also below the maximum distance threshold. In this case, the ‘moveForward()’ function is called to make the car move forward.

else if (frontDistance < leftDistance && frontDistance < rightDistance && frontDistance < MAX_DISTANCE) {
    moveForward();
    Serial.println("forward");

If the previous condition is false, this condition is checked. It verifies if the left distance is less than the right distance and less than the ‘MAX_DISTANCE’ threshold. This condition indicates that the left distance is the smallest among the three distances, and it is also below the minimum distance threshold. Therefore, the ‘turnLeft()’ function is called to make the car turn left.

else if (leftDistance < rightDistance && leftDistance < MAX_DISTANCE) {
    turnLeft();
    Serial.println("left");

If neither of the previous conditions is met, this condition is checked. It ensures that the right distance is less than the ‘MAX_DISTANCE’ threshold. This condition suggests that the right distance is the smallest among the three distances, and it is below the minimum distance threshold. The ‘turnRight()’ function is called to make the car turn right.

else if (rightDistance < MAX_DISTANCE) {
    turnRight();
    Serial.println("right");

If none of the previous conditions are true, it means that none of the distances satisfy the conditions for movement. Therefore, the ‘stop()’ function is called to stop the car.

 else {
    stop();
    Serial.println("stop");

In summary, the code checks the distances from the three ultrasonic sensors and determines the direction in which the car should move based on the 3 ultrasonic sensors with the smallest distance.

 

Important aspects of this Arduino-powered human-following robot project include:

  • Three-sensor setup for 360-degree human identification
  • Distance measurement and decision-making in real-time
  • Navigation that operates automatically without human assistance
  • Avoiding collisions and maintaining a safe following distance

 

 

Technical Summary and GitHub Repository 

Using three HC-SR04 ultrasonic sensors and an L298N motor driver for precise directional control, this Arduino project shows off the robot's ability to track itself. For simple replication and modification, the full source code, circuit schematics, and assembly guidelines are accessible in our GitHub repository. To download the Arduino code, view comprehensive wiring schematics, and participate in the open-source robotics community, visit our GitHub page.

Code Schematics Download Icon

 

Frequently Asked Questions

⇥ How does an Arduino-powered human-following robot operate?
Three ultrasonic sensors are used by the Arduino-powered human following robot to determine a person's distance and presence. After processing this data, the Arduino manages motors to follow the identified individual while keeping a safe distance.

⇥ Which motor driver is ideal for an Arduino human-following robot?
The most widely used motor driver for Arduino human-following robots is the L298N. Additionally, some builders use the L293D motor driver shield, which connects to the Arduino Uno directly. Both can supply enough current for small robot applications and manage 2-4 DC motors.

⇥ Is it possible to create a human-following robot without soldering?
Yes, you can use motor driver shields that connect straight to an Arduino, breadboards, and jumper wires to construct a human-following robot. For novices and prototyping, this method is ideal.

⇥ What uses do human-following robots have in the real world?
Shopping cart robots in malls, luggage-carrying robots in airports, security patrol robots, elderly care assistance robots, educational demonstration robots, and companion robots that behave like pets are a few examples of applications.

 

Conclusion

This human following robot using Arduino project and three ultrasonic sensors is an exciting and rewarding project that combines programming, electronics, and mechanics. With Arduino’s versatility and the availability of affordable components, creating your own human-following robot is within reach.

Human-following robots have a wide range of applications in various fields, such as retail stores, malls, and hotels, to provide personalized assistance to customers. Human-following robots can be employed in security and surveillance systems to track and monitor individuals in public spaces. They can be used in Entertainment and events, elderly care, guided tours, research and development, education and research, and personal robotics.

They are just a few examples of the applications of human-following robots. As technology advances and robotics continues to evolve, we can expect even more diverse and innovative applications in the future.

Explore Practical Projects Similar To Robots Using Arduino

Explore a range of hands-on robotics projects powered by Arduino, from line-following bots to obstacle-avoiding vehicles. These practical builds help you understand sensor integration, motor control, and real-world automation techniques. Ideal for beginners and hobbyists, these projects bring theory to life through interactive learning.

 Simple Light Following Robot using Arduino UNO

Simple Light Following Robot using Arduino UNO

Today, we are building a simple Arduino-based project: a light-following robot. This project is perfect for beginners, and we'll use LDR sensor modules to detect light and an MX1508 motor driver module for control. By building this simple light following robot you will learn the basics of robotics and how to use a microcontroller like Arduino to read sensor data and control motors.

Line Follower Robot using Arduino UNO: How to Build (Step-by-Step Guide)

Line Follower Robot using Arduino UNO: How to Build (Step-by-Step Guide)

This step-by-step guide will show you how to build a professional-grade line follower robot using Arduino UNO, with complete code explanations and troubleshooting tips. Perfect for beginners and intermediate makers alike, this project combines hardware interfacing, sensor calibration, and motor control fundamentals.

Have any question related to this Article?

How to Connect the LiteWing ESP32 Drone to Betaflight

Submitted by Vishnu S on

LiteWing is an open-source ESP32-S3 based drone that offers a flexible platform for experimentation and learning. By default, LiteWing operates using the modified Crazyflie firmware. LiteWing can also be configured using Betaflight, a powerful and widely adopted flight control software used in FPV and racing drones.

In this ESP32 Betaflight tutorial, we will go through the process of configuring the LiteWing drone Betaflight and turning it into a fully tunable drone. LiteWing drone Betaflight integration unlocks a rich set of features such as PID tuning, motor configuration, receiver setup, flight modes, and real-time diagnostics, making it an excellent choice for users who want deeper control over their drone’s behavior.

This ESP32 Betaflight configurator guide is for beginners as well as experienced developers who want to explore how open-source hardware like LiteWing can be integrated with standard flight software. By the end of this ESP32 Betaflight tutorial, you will have a properly configured LiteWing drone and a clear understanding of how ESP32 Betaflight firmware can be used to unlock its full potential. If you want to learn more about the LiteWing drone, its hardware, and other features, make sure to check out the official documentation and resources.

What You'll Learn in This ESP32 Drone Betaflight Tutorial:

  • Flashing the ESP32 Betaflight firmware to your LiteWing drone.
  • Setting up and optimising your ESP32 Betaflight Configurator.
  • Pin configuration for the correct communication between compatible hardware.
  • Integrating your ExpressLRS receiver with Betaflight.
  • PID tuning of the brushed motor drone.
  • Configuring your flight modes and enabling your Blackbox Data Log.

Pre-Requirements for LiteWing Betaflight Configuration

To follow this tutorial, you will need a LiteWing drone, an ExpressLRS (ELRS) receiver, and a compatible ELRS transmitter to control the drone. The receiver and transmitter should already be bound before connecting to the drone. A computer with Betaflight Configurator installed is also required for configuration and tuning. This ESP32 Betaflight configurator setup requires proper hardware connections.

Hardware Requirements:

» LiteWing ESP32-S3 drone with all components assembled
» ExpressLRS (ELRS) receiver for low-latency radio communication
» Compatible ELRS transmitter (pre-bound to receiver)
» USB data cable for computer connection
» LiPo battery suitable for LiteWing drone

Software Requirements:

» Betaflight Configurator v10.10.0 is installed on your computer
» Web browser (Chrome or Edge) for ESP flashing tool
» ESP32 Betaflight firmware binary file for ESP32-S3

⇒ Step 1: Uploading ESP32 Betaflight Firmware to LiteWing Drone

Before configuring the LiteWing ESP32 drone Betaflight firmware must be programmed manually using the ESP flashing tool. LiteWing uses an ESP32-S3 based ESP-FC, so the correct binary file must be flashed before proceeding.

Downloading the ESP32 Betaflight Firmware

First, open the ESP-FC open-source GitHub repository using the link below. This firmware is developed and maintained by rtlopez, and his work is highly appreciated for contributing to the open-source community.
GitHub Repository: https://github.com/rtlopez/esp-fc
Once the repository page opens, navigate to the Releases section. The releases page contains precompiled firmware binaries for different ESP based flight controllers. From there, download the firmware .zip  file specifically built for the ESP32-S3 microcontroller since LiteWing is based on the ESP32-S3 platform.

ESP32-S3 Firmware Download

To flash the firmware onto the LiteWing drone, open the Espressif ESP Tool (Web-based flasher) in a supported browser. Connect the LiteWing drone to your computer using a USB data cable, ensuring the drone is powered on and detected by your system. On the ESP Tool web page, click Select Port, choose the COM port corresponding to the LiteWing drone from the pop-up list and confirm the selection. Then click Connect to establish communication between the tool and the drone. Once connected successfully, the tool will be ready for firmware upload.

 Firmware Flash Setup in ESP Tool

Upload the downloaded firmware file (firmware_0x00.bin) and set the flash address to 0x0000, verifying that both the correct file and address are selected. Click the Program button to begin flashing and wait until the process completes successfully, making sure not to disconnect the drone during programming. Once finished, the firmware will be successfully uploaded to the LiteWing drone, and you can now proceed to configure settings and tune the drone using Betaflight. Once the ESP32 Betaflight firmware upload completes successfully, your LiteWing drone is ready for configuration in Betaflight Configurator.

Flashing ESP32 Betaflight Firmware Using a Web-Based Tool

Step

  Action

              Details

1

Open ESP Tool

Navigate to  Espressif ESP Tool in Chrome or Edge browser

2

Connect Drone

Connect LiteWing to computer via USB data cable, ensure drone is powered on

3

Select Port

Click "Select Port" and choose the COM port for LiteWing from the list

4

Establish Connection

Click "Connect" to establish communication with the ESP32-S3

5

Upload Firmware

Select firmware_0x00.bin file and set flash address to 0x0000

6

Program Device

Click "Program" and wait for completion (do not disconnect during flashing)

⇒ Step 2: Installing Betaflight Configurator for ESP32 Configuration

To configure and tune the LiteWing ESP32 Betaflight drone, you need the Betaflight Configurator installed on your computer. This software allows you to connect to the drone and adjust flight settings.

Downloading and Installing Betaflight Configurator

Visit the official GitHub release page for Betaflight Configurator Releases and download version 10.10.0 is recommended for easy setup. Choose the version compatible with your operating system: Windows, macOS, or Linux.

Configuring Betaflight Configurator Options

Download Betaflight Configurator v10.10.0

After installing and opening the ESP32 Betaflight configurator.

Before connecting the LiteWing ESP32 drone to Betaflight, you should adjust some settings in the Options tab as shown in the reference image. Make sure to enable “Show All Serial Devices” this ensures that the software can detect the drone even if it doesn’t appear by default.

These changes help the Betaflight Configurator communicate properly with the drone.

Betaflight Options Tab Configuration

Once the settings are updated, manually select the COM port in the software and click the Connect button to establish communication between the software and the drone.

⇒ Step 3: Configuring Hardware Pins via Betaflight CLI

When you first connect the LiteWing ESP32 drone to Betaflight, you may notice that the real-time updates and the 3D model in the setup tab do not respond correctly when the drone is moved. This happens because the default pin assignments in Betaflight do not match the LiteWing hardware. To fix this, you can update the pin assignments using the CLI tab in Betaflight Configurator. By entering the correct commands, you can map the pins according to LiteWing’s configuration, ensuring that all motors and sensors respond accurately during real-time updates.

Configuring Pins via Betaflight CLI

ESP32 Betaflight CLI Pin Configuration Commands

Navigate to the CLI tab in Betaflight Configurator and enter the following commands. These commands configure all necessary GPIO pins for the LiteWing ESP32 drone:

set pin_input_rx -1
set pin_output_0 6
set pin_output_1 5
set pin_output_2 3
set pin_output_3 4
set pin_buzzer 8
set pin_serial_0_tx 43
set pin_serial_0_rx 44
set pin_serial_1_tx 17
set pin_serial_1_rx 18
set pin_serial_2_tx -1
set pin_serial_2_rx -1
set pin_i2c_scl 10
set pin_i2c_sda 11
set pin_input_adc_0 2
set pin_input_adc_1 -1
set pin_spi_0_sck 12
set pin_spi_0_mosi 35
set pin_spi_0_miso 37
set pin_spi_cs_0 -1
set pin_spi_cs_1 7
set pin_spi_cs_2 -1
set pin_buzzer_invert -1

After pasting the commands, simply press Enter, then type save and press Enter again to save the changes. And then type reboot and press Enter again to apply the changes. This will update the pin configuration automatically, making the setup quick and easy without manually changing each assignment.

After the CLI commands are executed, simply disconnect and reconnect the LiteWing drone. This will allow the ESP32 drone to connect with  Betaflight Configurator and to display real-time updates, reflecting the drone’s movements accurately.

Pin Configuration Changes Applied 

The following pin configuration changes are implemented to match the LiteWing hardware setup.

Pin Type          GPIO AssignmentFunction
Motor Output 1GPIO 6Front-right motor PWM control
Motor Output 2GPIO 5Rear-right motor PWM control
Motor Output 3GPIO 3Rear-left motor PWM control
Motor Output 4GPIO 4Front-left motor PWM control
UART1 TX/RXGPIO 17/18ExpressLRS receiver communication
I2C SCL/SDAGPIO 10/11IMU sensor communication (MPU6050)
ADC InputGPIO 2Battery voltage monitoring

⇒ Step 4: Correcting IMU Orientation in LiteWing Betaflight Drone

After configuring the GPIO pins in your ESP32 Betaflight configurator, you may notice that the 3D model moves when the LiteWing drone is tilted or rotated, but the movements don't exactly match the actual drone orientation. The 3D model in Betaflight moves when the drone is tilted or rotated, but you may notice that its movements do not exactly match the actual drone. This happens because the IMU (Inertial Measurement Unit) on the LiteWing is placed in a different orientation. To correct this, go to the Configuration tab in Betaflight, scroll to Board and Sensor Alignment, and change the First Gyro setting from Default to CW 270°. This aligns the 3D model accurately with the real movements of the drone.

Correcting IMU Orientation in Betaflight

 

⇒ Step 5: Battery Voltage Monitoring Configuration

To monitor the battery voltage in the software, make the necessary changes as shown in the reference image below, select Onboard ADC as the voltage meter source and then set the minimum and maximum cell voltage values, and adjust the warning cell voltage according to your requirements.

Configuring Battery Indicator in Betaflight

In the voltage meter settings, set the scale to 10, the divider value to 1, and the multiplier value to 2, as these values are calculated based on the voltage divider used in the LiteWing.

Voltage Divider Calibration for LiteWing ESP32 Drone

ParameterValuePurpose
Voltage Scale10ADC reading multiplier for voltage calculation
Voltage Divider1Hardware divider ratio (pre-calculated in scale)
Voltage Multiplier2Correction factor for LiteWing's voltage divider circuit

After entering these values, click Save and Reboot to apply the battery monitoring configuration to your ESP32 Betaflight firmware.

⇒ Step 6: Configuring Motor Protocol for Brushed DC Motors

LiteWing ESP32 drone uses brushed DC motors, so the motor protocol must be configured accordingly in Betaflight. In the Configuration tab of Betaflight Configurator, set the Motor Protocol to Brushed. Then set the Motor PWM Frequency to 8000 Hz. Keep the remaining motor and ESC-related parameters set as shown in the reference image, as these values are configured for the LiteWing hardware.

Motor Protocol Setup in Betaflight

After making these changes, click Save and Reboot to apply the settings. Once completed, the motors will respond correctly and smoothly during operation.

⇒ Step 7: Connecting and Configuring ExpressLRS Receiver

In this setup, we are going to control the LiteWing drone using a radio transmitter and receiver. For this setup, we are using an ExpressLRS (ELRS) receiver due to its low-latency radio communication. ELRS is widely used due to its long range, fast response, and open-source support.

Connecting ELRS Receiver to LiteWing Drone

Connect the ELRS receiver to the LiteWing according to the UART wiring. Power the receiver using 3.3V and GND. Connect the receiver’s TX pin to the drone’s RX (GPIO18), and the receiver’s RX pin to the drone’s TX (GPIO17). Ensure all power, ground, and signal connections are properly made before proceeding.

Why Choose ExpressLRS for ESP32 Betaflight Drones?

Ideal for use within LiteWing Ctrl ESP32 Drone, ExpressLRS Receivers offer the following advantages:

∗ Ultra-low latency - Instantaneous feedback to commands and immediate changes to airframe attitude, with receipt of command inputs occurring at ultra-low latencies (as little as 5ms).

∗ Long distances - An excellent range of operation — several kilometres, assuming optimal use of antennas.

∗ Open Source Protocol - Firmware is open source; support from a community of users.

∗  CRSF Protocol - Fully compliant with the Betaflight CRSF Receiver Mode.

ELRS Receiver PinLiteWing GPIO PinConnection Purpose
VCC (3.3V)3.3V PowerReceiver power supply
GNDGNDCommon ground connection
TXGPIO 18 (RX)Receiver transmits data to drone
RXGPIO 17 (TX)Receiver receives data from drone

Next, open Betaflight Configurator and go to the Ports tab. Enable Serial RX on the UART 2, where the ELRS receiver is connected, and save the settings.

Enabling Serial RX for ELRS in Betaflight

Then go to the Receiver tab, set the Receiver Mode to Serial-based receiver, and select CRSF as the protocol. Save and reboot the drone. After this, power on the transmitter if everything is configured correctly, and you will see real-time channel movements in the Receiver tab when you move the transmitter sticks.

Configuring ELRS Receiver in Betaflight

⇒ Step 8: Configuring Flight Modes for LiteWing Betaflight Drone

Flight modes define how the LiteWing drone behaves during flight. In this setup, we will configure ARM, ANGLE, and BLACKBOX modes using Betaflight.

Configuring Flight Modes in Betaflight

Understanding Flight Modes for ESP32 Drones

Flight Mode

                 Purpose

Recommended For

ARM

Enables/disables motor output for safety

All flights (mandatory)

ANGLE

Self-leveling mode with automatic stabilization

Beginners, stable indoor flights

ACRO

Full manual control with no self-leveling

Advanced pilots, aerobatics

BLACKBOX

Records flight data for analysis and tuning

PID tuning, troubleshooting

Open the Modes tab in Betaflight Configurator. Assign a switch on your transmitter to the ARM mode to enable and disable the motors safely. Next, assign another switch or position to ANGLE mode, which provides self-levelling and is ideal for stable and beginner-friendly flight. Enable BLACKBOX mode to record flight data for tuning and troubleshooting.

Enabling ARM, ANGLE, and Blackbox Modes

After assigning the switches, make sure the activation ranges are set correctly and click Save. These modes will allow you to arm the drone and switch between stable and aggressive flight behavior as needed.

⇒ Step 9: PID Tuning for LiteWing Brushed Motor Drone

The default PID values in ESP32 Betaflight firmware are not suitable for the LiteWing drone and can result in unstable flight performance. Since LiteWing is a lightweight drone using brushed DC motors, custom PID values are required to achieve stable and smooth flight.

In the PID Tuning tab of Betaflight Configurator, replace the default values with the recommended LiteWing PID values provided in the reference configuration. These values have been tested and optimized specifically for LiteWing and help eliminate oscillations while improving control and responsiveness.

Configuring Recommended PID Values

After entering the PID values, click Save and perform a short test flight. If required, minor adjustments can be made later, but the provided values should give a stable and reliable flying experience right away.

Why Custom PID Values for LiteWing ESP32 Drone?

The LiteWing drone requires custom PID tuning because:

∗ Low weight construction: The reduced weight necessitates changes to PID (proportional, integral and derivative) settings for the model.
∗ Brushed motor technology (coreless): Torque curves with different speed exponentials compared to the brushless motor.
∗ Small propellers: Lower inertia creates a need for different stabilization procedures than those required by larger props.
∗ Compact design: The shorter arm lengths between motors affect the rotational characteristics of the various components.

⇒ Step 10: Blackbox Flight Data Recording and Analysis

Blackbox is a logging feature in Betaflight that records flight data such as gyro values, motor outputs, PID behavior, and receiver inputs. This data is useful for analyzing flight performance and troubleshooting issues like vibrations, oscillations, or unstable behavior.

Betaflight Blackbox Flight Data Logging

After enabling Blackbox in Betaflight, fly the LiteWing drone to record flight data. Once the flight is complete, connect the drone to Betaflight Configurator, go to the Blackbox tab, and download the log files. Open these logs in the Betaflight Blackbox Explorer to analyze gyro data, PID behavior, and vibrations, which help in improving stability and tuning performance.

After completing all the steps in this guide, your LiteWing drone configured with Betaflight is fully ready for flight. You can now safely test it, fine-tune settings if needed, and explore more advanced Betaflight features as you gain experience.

Troubleshooting Common ESP32 Betaflight Issues

Issue

Possible Cause

Solution

Motors not spinning

ARM mode not activated or motor protocol wrong

Verify ARM switch position and brushed motor protocol

Drone drifts in ANGLE mode

IMU not calibrated or accelerometer offset

Recalibrate accelerometer on level surface in Setup tab

No receiver signal

UART wiring incorrect or wrong protocol

Verify ELRS wiring and CRSF protocol selection

Battery voltage incorrect

ADC calibration values wrong

Verify scale=10, divider=1, multiplier=2

Frequently Asked Questions About ESP32 Betaflight Tutorial

⇥ 1. How to calibrate the IMU?
To calibrate the IMU (Inertial Measurement Unit) in Betaflight, place the LiteWing drone on a flat and stable surface. Open Betaflight Configurator and connect the drone. Go to the Setup tab and click the Calibrate Accelerometer button. Keep the drone completely still during the calibration process. Once finished, the IMU will be calibrated, ensuring accurate orientation and stable flight behavior.

⇥ 2. Why is my LiteWing not connecting to Betaflight Configurator?
After flashing or making configuration changes, disconnect and reconnect the drone, and ensure that no other applications (such as Arduino IDE, serial monitor, or ESP tools) are using the same COM port.

⇥ 3. Do I need to calibrate the accelerometer every time?
No, you do not need to calibrate the accelerometer every time you power on the LiteWing drone. Accelerometer calibration is usually required only once during the initial setup or after making major changes.

⇥ 4. How do I enable FPV (Acro) mode on the LiteWing drone?
Assign a switch for ARM and do not enable ANGLE mode.
When the angle mode is off, the LiteWing drone flies in FPV (Acro) mode.
 

Other LiteWing ESP32 Drone Projects

Beginner-friendly LiteWing drone projects that explore different ways to program, control, and experiment with ESP32 based drones, focusing on practical learning and real-world applications.

DIY Gesture Control Drone using Python with LiteWing and ESP32

DIY Gesture Control Drone using Python with LiteWing and ESP32

Build a gesture-controlled drone using ESP32 and LiteWing. This project explains how to track hand movements with MPU6050 and control the drone via Bluetooth and Python using UDP communication.

 How to Use Height Hold Mode in LiteWing ESP32 Drone?

How to Use Height Hold Mode in LiteWing ESP32 Drone?

Learn how to add height hold to the LiteWing ESP32 drone using the VL53L1X ToF sensor. This tutorial explains sensor setup, PID control, and app integration for smooth indoor flights.

 How to Program LiteWing Drone using Python with Crazyflie Cflib Python SDK

How to Program the LiteWing Drone using Python with Crazyflie Cflib Python SDK

Learn how to control the LiteWing drone using the Crazyflie cflib Python SDK. This guide covers installation, basic commands, and writing Python code to spin the drone's motors via Wi-Fi.

Have any question related to this Article?

Joule Thief Circuit: A Low-Power Voltage Booster

Submitted by Vishnu S on

The Joule Thief Circuit is a simple and clever electronic design that can power an LED using a nearly dead battery. The project demonstrates how basic components like a transistor, a toroidal coil, and a resistor can work together to boost a low input voltage to a usable output voltage. By building this circuit, we can explore how a nearly dead battery's energy can be used efficiently without wasting the energy in it. A Joule Thief circuit is a simple voltage booster that uses a toroidal coil, an NPN transistor, and a resistor to extract power from nearly dead batteries. It is a great project for understanding how inductive switching, voltage boosting, and energy-efficient design can be in a practical way. 

For a deeper understanding of boost converter concepts, including switching operation, design principles, and efficiency considerations, refer to Switching Boost Regulator: Design Basics and Efficiency. This resource provides clear explanations of how switching regulators work and how voltage boosting is achieved efficiently in practical circuits.

What is a Joule Thief Circuit

A Joule Thief circuit is a small, energy-efficient boost converter designed to extract usable power from very low-voltage sources such as “dead” or nearly drained batteries. It uses a transistor, a resistor, and a toroidal coil with two windings to step up the low input voltage and generate high-voltage pulses. These pulses are strong enough to power devices like LEDs, even when the battery voltage is too low to operate them directly.

The joule thief circuit working mechanism relies on rapid switching, turning the transistor ON and OFF many times per second, which stores and releases energy in the coil. This simple circuit is widely used to demonstrate energy harvesting, inductive switching, and efficient power utilisation, making it popular in hobby electronics, education, and low-power lighting applications. This joule thief circuit with toroid operates through self-sustained oscillation, rapidly switching the transistor between conduction and cutoff states thousands of times per second.

Joule Thief Circuit Components: Complete Parts List

The Joule Thief circuit has a minimal set of electronic components that are easy to obtain and assemble. Below the detailed table explaining each component and its purpose in the circuit.

ComponentsQuantityDescription Function in Circuit
NPN Transistor 
(eg.2N2222,2N3904)
1A small-signal transistorActs as a switch, controlling current flow through the coil and enabling voltage boosting
1 kΩ Resistor1Limits current to the transistor basePrevents excessive base current and ensures stable oscillation
Toroidal Coil1Small ferrite core with two windingsStores and releases magnetic energy; provides feedback to the transistor for oscillation
LED1Light Emitting DiodeConverts boosted voltage pulses into visible light
Battery (AA or AAA, 1.5V)1Low-voltage power sourceProvides input voltage, even if weak or partially discharged
Breadboard

1

prototyping boardAllows easy assembly and testing of the circuit without soldering
Connecting WiresAs neededcopper or jumper wiresConnects components to form the complete circuit

The image below displays all joule thief circuit components required for construction. It includes a toroidal inductor for energy storage, an NPN transistor for high-speed switching, a 1 kΩ resistor to control base current, an LED as the load, an AA battery as the low-voltage source, and a breadboard for easy prototyping and testing of the circuit. If you want to learn more about what an NPN transistor is and how it works, check out the article “NPN Transistors.

Joule Thief circuit components including toroidal inductor, NPN transistor 2N2222, 1kΩ resistor, LED,

Joule Thief Circuit Diagram: Schematic Explained

The joule thief circuit diagram shows how the transistor, resistor, LED, and the two windings on the toroid are connected. It clearly illustrates how the Joule Thief boosts a low battery voltage to power the LED.

Joule Thief Circuit Diagram showing toroid windings, NPN transistor, resistor, and LED connections

This Joule thief schematic clearly illustrates a simple Joule Thief circuit, showing how a low-voltage battery can be boosted to light an LED. In this setup, the core component is a Joule Thief circuit with a toroid, where the toroidal core carries two windings: the primary winding (1 & 2) for current flow and the feedback winding(3 & 4) for rapid switching. This layout helps you understand how the coil windings and the transistor work together to step up the voltage efficiently from even a nearly drained battery. This joule thief circuit diagram demonstrates the critical relationship between components.

Joule Thief Wiring Diagram: Practical Assembly Guide

This wiring diagram shows the practical implementation of the joule thief circuit with toroid, with clearly distinguished coil connections. The primary winding, which carries the main current from the battery, is shown using the red wire, while the feedback (switching) winding, which provides base drive to the transistor, is indicated using the yellow wire. The correct interaction between these two windings enables rapid transistor switching and voltage boosting to power the LED from a low-voltage battery.

oule Thief Circuit Wiring Diagram with color-coded toroid connections

Joule Thief Circuit Working Principle

Understanding the joule thief circuit working requires examining the electromagnetic interactions between the toroidal coil windings and the transistor switching behaviour. The Joule Thief uses a Toroidal coil with two windings :
1. Primary Coil - carries the main current from the battery 
2. Feedback (switching) Coil - controls the transistor switching 
Both coils work together to create a self-oscillating boost converter

⇒ Phase 1: Current Flows in the Primary Coil

When the battery is connected, a small current starts to flow through the primary coil and then to the transistor’s base through the resistor. This turns the transistor slightly ON, allowing current to flow through it. The magnetic field starts building in the primary coil due to the flow of current around the toroid.

⇒ Phase 2: Feedback Coil Activates the Transistor

As the magnetic field builds around the primary coil, it induces a voltage in the feedback(switching) coil. This process occurs due to the mutual inductance. The induced voltage is passed into the transistor, increasing the base current.

As a result, the transistor turns more ON, allowing more current to flow through the primary coil.

This is called the positive feedback, and it forces the transistor to full conduction.

⇒ Phase 3: Core Saturation Occurs

As current continues to flow through the primary winding, the magnetic field in the toroidal core keeps increasing until the ferrite core can no longer store additional magnetic flux. This condition is known as Magnetic Saturation.

Once the core reaches saturation, the induced voltage in the feedback coil starts to drop sharply, causing the base drive of the transistor to disappear. As a result, the transistor switches OFF abruptly.

⇒ Phase 4: Magnetic Field Collapse & High Voltage Spike

When the transistor switches OFF, the current flowing through the primary coil cuts off suddenly.

But the inductors resist the sudden change in the current flow, so the magnetic field collapses rapidly, which is stored in the primary coil. 

This collapse creates a high voltage spike across the primary coil. This spike is much higher than the original battery voltage and is enough to light up an LED.

⇒ Phase 5: Oscillation Begins Again

Once the transistor switches OFF, the current flow through the primary winding stops and the magnetic field in the toroid collapses to ZERO. After this, a small amount of current starts again to flow across the coil and into the transistor’s base through the resistor. This initiates the next switching cycle.

This repeated action causes the primary and feedback windings to continuously force the transistor to turn ON and OFF at high frequency. The frequency is between the hundreds and thousands of times per second, which produces rapid voltage pulses that keep the LED illuminated.

Joule Thief Circuit Simulation: Visual Working Demonstration

Here is the Simulation of the simple Joule thief circuit. It demonstrates how a low-voltage battery is able to power an LED through the rapid switching and voltage boosting. At the beginning, the current starts to flow through the primary winding, causing the transistor to switch ON. The feedback wing then reinforces the base drive, which results in rapid oscillation. The following simulation demonstrates the joule thief circuit working principles in real-time.

Animated Joule Thief Circuit Simulation showing transistor switching and LED operation

As seen in the simulation of the Joule Thief schematic, once the magnetic core reaches saturation, the transistor switches OFF, and the stored magnetic energy collapses, which results in a high-voltage spike across the primary winding. This voltage spike is sufficient to forward-bias the LED, allowing it to glow even though the battery voltage is very low.

The continuous ON & OFF switching cycle is clearly visible in the simulation, and it proves the self-oscillating nature of the Joule Thief Circuit and its ability to efficiently boost voltage from weak power sources.

Practical Working Demonstration: Video Evidence

This practical demonstration showcases a real-world joule thief circuit working behaviour. The LED does not glow when connected directly to the low-voltage battery, but it lights up when connected through the Joule Thief circuit. This happens due to rapid switching and voltage boosting using the toroidal coil. The demonstration confirms the circuit’s ability to utilise energy from weak batteries.

LED connected directly to weak battery showing no illumination

In the above video, the LED is directly connected to the battery, but it does not glow. This happens because the battery voltage is too low to overcome the LED’s forward voltage requirement. Although the battery still contains some energy, it is insufficient to drive current through the LED directly. This observation highlights the limitation of low-voltage sources and sets the foundation for using the Joule Thief circuit, which boosts the voltage and enables the LED to glow even from a weak battery.

Joule Thief Circuit Implementation

LED connected through Joule Thief Circuit showing bright illumination

When the LED is connected through the Joule Thief circuit with toroid, it starts glowing even with the same low-voltage battery. This is because the circuit boosts the battery’s voltage by rapidly switching the transistor and storing energy in the toroidal coil. The collapsing magnetic field generates high voltage pulses that are sufficient to forward bias the LED. This result clearly demonstrates the effectiveness of the Joule Thief circuit in extracting and utilising the remaining energy from weak batteries.

Practical Applications of Joule Thief Circuits

  • Powering LEDs from weak batteries - It can light an LED even when the battery voltage is too low for normal use.
  • Energy harvesting projects - Useful for extracting leftover energy from partially drained cells.
  • Portable emergency lights - Can be used in small flashlights to extend battery life.
  • Educational and hobby electronics - Helps students understand inductive switching, oscillation, and voltage boosting.
  • Low-power sensor circuits - Can drive small sensors or circuits that require a slightly higher voltage.
  • Battery testing demonstrations -  Shows visually how much energy remains in “dead” batteries.

What are some alternatives to the Joule Thief circuit?

∗ Supercharged Joule Thief circuit: The supercharged Joule Thief has a higher efficiency (greater than 80%) than other types of Joule Thief circuits that range from 40-60% efficiency.
∗ Buck-Boost Converters: Used for more powerful applications with a negative voltage output from an input voltage.
∗ Voltage multiplier: Converts lower-voltage AC electricity into DC electricity of a higher voltage.
∗ Split-pi Topology: DC-DC converters that have bidirectional capabilities due to the use of MOSFETs and are suited for regenerative braking systems.

Advantages and Disadvantages of the Joule Thief Circuit

AdvantagesDisadvantages
Can operate from very low input voltagesCan operate from very low input voltages
Utilizes energy from weak or “dead” batteriesOutput voltage is unregulated
Simple circuit with very few componentsNot suitable for high-current loads
Low cost and easy to buildEfficiency drops at higher loads
Self-oscillating (no external controller needed)Generates electrical noise due to switching
Ideal for learning voltage boosting conceptsCannot be used for battery charging
Compact and portable designPerformance depends on coil winding quality

Technical Limitations of the Joule Thief Circuit

  • Low Output Power:
    The Joule Thief can only deliver a small amount of power, making it suitable only for low-power loads such as LEDs.
  • Poor Voltage Regulation:
    The output voltage is not regulated and appears as high-voltage pulses, which are unsuitable for sensitive electronic devices.
  • Low Efficiency at Higher Loads:
    Efficiency decreases significantly when attempting to drive higher current or multiple loads.
  • Limited Current Capability:
    The circuit can boost voltage, but cannot supply high current.
  • Component Sensitivity:
    Performance depends heavily on the type of transistor, coil winding, and core material.
  • EMI and Noise:
    Rapid switching can generate electrical noise and electromagnetic interference.

Frequently Asked Questions About Joule Thief Circuit

⇥ 1. What is the minimum battery voltage needed?
The circuit can often run from as low as 0.8V, depending on components.

⇥  2. Why is it called a “Joule Thief”?
Because it “steals” the remaining energy (joules) from weak or “dead” batteries and makes them usable again.

⇥ 3. Why is a toroidal core used?
The toroid helps create strong magnetic coupling between the two windings, making the switching process efficient.

⇥ 4. Can I use any NPN transistor?
Most general-purpose NPN transistors (like 2N3904, BC547, or 2N2222) will work.

⇥ 5. How does the circuit boost voltage?
It uses a transistor and a two-winding coil to store energy in a magnetic field and release it as high-voltage pulses when the transistor switches OFF.

⇥ 6. Why does the circuit oscillate automatically?
Because the feedback winding sends a signal that rapidly turns the transistor ON and OFF, creating a self-sustaining oscillation cycle.

⇥ 7. Can the Joule Thief charge batteries?
Not directly. It boosts voltage but does not regulate current, so it's not suitable for battery charging without modifications.

⇥ 8. What is the typical operating frequency range of a Joule Thief circuit?
Joule Thief circuits normally operate at oscillation frequencies between 50 and 500 kHz, which are mainly influenced by various factors such as the type of core used for the toroid, the number of turns in the winding, the properties of the transistor, and the load applied.

This tutorial was created by the CircuitDigest engineering team. Our experts focus on creating practical, hands-on tutorials to help makers and engineers learn Raspberry Pi projects, Arduino projects, Electronic Circuit projects and more. 

I hope you liked this article and learned something new from building the Joule Thief circuit. If you have any doubts, you can ask in the comments below or use our CircuitDigest forum for a detailed discussion.
 

A simple collection of beginner-friendly electronics circuits and concepts, covering LED control, 555 timer applications, boost converters, and basic transistor operation.

 Single Cell Boost Converter Circuit using Coin Cell – 5V Output

Single Cell Boost Converter Circuit using Coin Cell – 5V Output

In this project, we build a low-cost 5V booster circuit that provides a constant regulated output voltage of 5V from a CR2032 coin cell.

 A Simple DC-DC Boost Converter using 555 Timer IC

A Simple DC-DC Boost Converter using 555 Timer IC

In this project, we build a simple boost converter circuit using a 555 timer IC. A boost converter is a non-isolated type of switch-mode power supply that is used to step up the voltage. 

Simple Flashing LED using 555 Timer IC

Simple Flashing LED using 555 Timer IC

This tutorial will show you how to make an LED glow and fade on a certain interval. So here is the step by step guide to make this flashing LED circuit.

 1W LED Driver Circuit

1W LED Driver Circuit

This tutorial shows how to design a high-power LED driver circuit using the LM317 IC. It covers current limiting basics, resistor calculations, power ratings, and practical breadboard testing for reliable LED operation.

Have any question related to this Article?