1. Introduction
Mobile robotic platforms have been enhanced by advancements in microelectronics, sensors, and wireless technologies, enabling advanced control systems to become more affordable to researchers and educators. Self-balancing robots represent a challenging subset of mobile robotics, behaving like inverted pendulum systems that continuously require real-time adjustments to maintain stability [
1].
The inherent instability of self-balancing robots makes them valuable platforms for studying control theory, sensor integration, and real-time processing. The dynamic balancing problem requires the application of control engineering principles combined with efficient sensor fusion algorithms [
2].
The ESP32 microcontroller-based platform provides a cost-effective and high-performance base for robotics applications, offering a dual core processor, embedded Wi-Fi and Bluetooth, and a multitude of general purpose input output (GPIO) pins for communication with sensors and actuators [
3]. Supplemented by IMUs (e.g., MPU6050), this hardware combination can run sophisticated control algorithms with relatively modest resource requirements. This device is a versatile platform with the possibility of operating wirelessly (Bluetooth communication functionality) for remote control and monitoring (telemetry) using standard mobile devices [
4].
This work includes a comprehensive investigation of a self-balancing robot system using the ESP32 microcontroller, MPU6050 IMU sensor, Android application over Bluetooth, and motor encoders and ultrasonic distance sensors. This system includes real-time telemetry visuals, autonomous obstacle avoidance features, and data recording. While sensor readings can be provided to the microcontroller in a steady-state form, balanced control of the robotic system, as well as rich user feedback and interaction, is supported through distributed processing between the microcontroller 10 and mobile device 11 [
5].
The system architecture highlights the interface between the ESP32 microcontroller on the physical robot and an Android device through which all user inputs will be sent to the robot. This distributed structure leverages the strengths of both components: the real-time capabilities of the microcontroller for sensor processing and motor control and the computational and display capabilities of the mobile device for data visualization and user interaction [
6]. Bi-directional Bluetooth communication enables command transmission from the Android device to the robot and telemetry data transmission back to the application for processing and visualization [
7].
This work introduces the following contributions: (1) a progressive calibration process that dynamically compensates for gyroscope drift during operation, (2) an efficient computational model for dual-platform architecture by distributing tasks between ESP32 and Android device, (3) a balancing obstacle avoidance system that maintains balance while navigating around obstacles, and (4) smart battery management that adjusts control parameters based on available capacity.
2. Literature Review
Self-balancing robots represent an interdisciplinary domain intersecting areas such as control systems, embedded computing, sensor fusion, and human–robot interaction. This literature review examines key developments in these areas and establishes connections to the objectives of the current study.
2.1. Self-Balancing Robot Systems
At the core of self-balancing robots is the problem of the instability of the inverted pendulum system. Early work by Tomašić et al. [
1] laid the mathematical groundwork for the inverted pendulum problem relevant to robotic applications, and Martins and Nunes [
5] demonstrated one of the first complete self-balancing robot designs and showed the viability of real-time control for maintaining balance on a two-wheeled platform.
Building on these foundations, Iwendi et al. [
8] studied advanced control algorithms comparing PID, fuzzy logic, and state-space controllers for balance maintenance in multiple scenarios. They found that PID controllers provided a simple, robust solution for maintaining balance, while more advanced methods such as state-space control achieved better performance in terms of maneuver complexity and disturbance rejection.
The overall system architecture integrating these components is illustrated in
Figure 1, which shows the distributed processing approach with real-time control on the ESP32 and user interface management on the Android device.
The development of miniaturized MEMS-based inertial sensors has played a significant role in the evolution of self-balancing platforms. An extensive study of different sensor fusion techniques for accurate orientation estimation, a critical factor for balance control, was conducted by Malathi and Ramchandran [
9]. Recognizing the computational cost of traditional integrated measurement systems such as Kalman filtering for combining accelerometer and gyroscope readings in battery-powered devices, their work showed that complementary filtering can be a computationally efficient alternative.
Recent work by Rengaraj et al. [
10] focused on adaptive control methods that can adjust parameters in real-time in response to changing system parameters, enhancing robustness against variations in payload, battery voltage, and surface friction. Similarly, Nguyen et al. [
11] achieved improved stability using a cascaded control framework that separated orientation and position control layers.
2.2. Microcontroller Platforms for Mobile Robotics
The selection of appropriate microcontroller platforms has been a key factor in the design of advanced mobile robots. Foltýnek et al. [
12] highlighted the advantages of using ESP32 for computationally intensive control tasks, utilizing both cores to ensure real-time control performance.
Mittal et al. [
13] investigated the integration of multiple sensors with microcontrollers, evaluating various interfacing strategies and their impact on system performance. They concluded that optimized I2C communication and interrupt-based sensor reading significantly improved control loop consistency, which is crucial for balance-sensitive applications.
The various aspects of motor control as applied to self-balancing robots have been extensively addressed by Tharun et al. [
14], which included PWM methods and their influence on motor response characteristics. Siddhartha and Ghosh [
15] focused on resource-constrained programming for mobile robots, providing optimizations for real-time control systems. Their work highlighted the importance of efficient memory utilization and computational resource allocation for implementing complex algorithms, such as sensor fusion and PID control, on constrained embedded devices.
2.3. Bluetooth Communication in Robotic Applications
Wireless communication for mobile robots presents challenges related to latency, reliability, and power consumption. Bluetooth Classic and Low Energy have been widely studied in robotics applications. Top and Gökbulut [
16] presented a comprehensive study of BLE networking capabilities for reliable command and telemetry system design.
Li et al. [
17] reported a comparative study of Bluetooth for real-time control applications. The latency characteristics and packet loss rates in various scenarios are important for remote robot control. Their work established practical guidelines for optimizing Bluetooth parameters to achieve consistent command transmission with minimized delays. Integrating Bluetooth communication with Android devices for robotics applications was explored by Santo and Garcia [
18], who developed frameworks for establishing reliable connections and handling data exchange between mobile applications and microcontroller-based robots. Their approach to packet formatting and command protocol design informed the communication structure implemented in this study.
Recent advancements in wireless control systems for mobile robotics have explored alternative input modalities beyond traditional manual interfaces. Gupta et al. [
19] developed a speech-recognition-based wireless control system that demonstrates the potential for more intuitive human–robot interaction, providing insights into advanced wireless communication protocols and user interface design that complement the touch-based Android interface implemented in this study.
2.4. Control Algorithms for Self-Balancing Systems
The control algorithm is the core of a self-balancing robot system, with complexity increasing as performance and robustness requirements improve. Classic PID control has been extensively studied by Zimit et al. [
20], who provided detailed design guidelines for two-wheeled balancing robots. Their focus was on tuning methodologies and the relationship between PID parameters and physical robot characteristics. Alternative control strategies, such as Linear Quadratic Regulators (LQRs), have been compared to PID approaches by Abdelgawad et al. [
21], who found that while LQR controllers offered superior theoretical performance, properly tuned PID controllers often provided comparable practical results with significantly reduced computational requirements. This is particularly relevant for resource-constrained microcontroller platforms.
Park and Cho [
22] addressed the problem of gyroscope drift in balance control systems by developing calibration and compensation strategies for sensor bias errors over time. Their method for continuous recalibration during operation has influenced the drift compensation techniques used in the present study.
Recent work by Setiawan and Syauqy [
23] explored machine learning approaches to balancing control, using neural networks to develop control policies that adapt to changing conditions and robot configurations. Although these methods show promise for future work, they are currently too computationally expensive for practical implementation on most microcontroller-based systems.
2.5. Sensor Fusion and State Estimation
Accurate state estimation is essential for self-balancing robots as they rely on fusing information from multiple sensors. The complementary filter approach, popularized in the work of Mai et al. [
24], provides a computationally efficient method for combining accelerometer and gyroscope measurements. When properly implemented, complementary filters can achieve performance comparable to more complex Kalman filter implementations.
Muñoz-Hernandez et al. [
25] analyzed extended Kalman Filter (EKF) implementations for microcontroller-based platforms, adapting the algorithms for real-time execution on limited hardware. These methods, while more computationally expensive than complementary filters, achieve higher accuracy in dynamic environments.
Kalatuwage et al. [
26] evaluated different sensor configurations and filtering techniques to improve reliability in varied environments. Their findings regarding optimal sensor positioning and reading intervals inspired the implementation of the obstacle avoidance system in this study.
2.6. Research Gap and Contributions
The literature indicates that there is room for further research in several areas. While many works have focused on individual components of self-balancing robots, fewer studies present comprehensive systems that integrate advanced control algorithms, wireless communication, and user interfaces. Quantitative performance analysis of complete systems under various operating conditions is also limited in the existing literature.
This study seeks to address this gap by providing a comprehensive analysis of an integrated self-balancing robotic system, including detailed implementation insights, performance metrics, and design considerations. By combining established control techniques with modern microcontroller technology and mobile device integration, this research contributes to the development of accessible yet sophisticated robotics platforms.
3. Theoretical Background
This section establishes the theoretical foundations of the self-balancing robot system, incorporating concepts from dynamics, control theory, sensor fusion, and communication protocols. These principles guide the design choices and implementation methodologies.
3.1. PID Control Framework
The primary control algorithm implemented in this study is a Proportional–Integral–Derivative (PID) controller, selected for its effectiveness, computational efficiency, and tuning accessibility. The PID controller generates a control signal based on the error between the desired pendulum angle (typically zero) and the measured angle:
where
is the control signal applied to the motors,
is the error signal (difference between desired and actual angle), and
,
, and
are the proportional, integral, and derivative gains, respectively.
Each component of the PID controller serves a specific purpose: the proportional term provides an output proportional to the current error; the integral term addresses steady-state errors by accumulating past errors; the derivative term improves transient response by predicting future error based on its rate of change.
When the PID equation is applied in discrete time, as required for microcontroller-based systems, the equation becomes
where
is the sampling period, and
n represents the discrete time index.
For this specific robot implementation, the PID parameters were systematically tuned using the Ziegler–Nichols method followed by empirical refinement to —providing sufficient responsiveness to angular deviations, —addressing gradual drift without causing oscillations, and —dampening oscillations while maintaining responsive control. The tuning process involved 15 iterations with quantitative performance assessment at each stage.
3.2. Sensor Fusion Algorithm
Accurate angle estimation is crucial for self-balancing control. While accelerometers can provide absolute angle measurements relative to gravity, they are susceptible to noise from motor vibrations and external forces. Gyroscopes offer precise angular rate measurements but suffer from integration drift over time. A complementary filter approach combines the strengths of both sensors:
where
is the final angle estimation,
is the angle change measured by the gyroscope (
),
is the previous estimated angle,
is the angle calculated from accelerometer data (
), and
is a filter coefficient between 0 and 1, typically set to 0.98.
This approach provides a computationally efficient method of combining the high-frequency accuracy of the gyroscope with the long-term stability of the accelerometer. The filter coefficient
determines the cut-off frequency of the filter, effectively specifying which sensor dominates in different frequency ranges, as shown in the sensor fusion flowchart in
Figure 2.
3.3. Bluetooth Communication Protocol
Communication between the Android device and ESP32 microcontroller utilizes the Bluetooth Serial Port Profile (SPP), which enables reliable stream-oriented data transfer. The protocol is implemented as a lightweight, efficient messaging layer with distinct formats for commands and telemetry data (
Figure 3).
From an android device, identifiable outputs of user are transmitted in a simple single byte command protocol to the ESP32: “F” for Forward Motion, “B” for Backward Motion, “L” for Left Turn, “R” for Right Turn, “S” for Stop all Motion, “C” for Calibrate Sensors, “A” for Autonomous Mode, and “M” for Manual Mode.
This aids in reducing transmission overhead, simplifying command parsing on the ESP32, and lowers the overall latency.
The ESP32 to Android telemetry data transmission uses a structured binary packet format: Bytes 0–3: tilt angle (float, little-endian); Bytes 4–5: front distance in cm (uint16); Bytes 6–7: back distance in cm (uint16); Bytes 8–11: left motor speed RPM (float, little-endian); Bytes 12–15: right motor speed RPM (float, little-endian); Byte 16: obstacle flags: sleeping = none/front = 1/back = 2; Byte 17: battery level percentage (uint8); Bytes 18 to 19: reserved for future use.
The binary format allows transmitting multiple sensor values in one packet, which reduces the transmission time and bandwidth a lot and at the same time gives us an extensive state information for visualizing/logging [
18]. The complete communication protocol structure is detailed in
Figure 3.
3.4. Motor Control System
The motor control system utilizes Pulse Width Modulation (PWM) to regulate the speed and direction of two DC motors through an H-bridge driver. The relationship between the PWM duty cycle and the motor torque can be modeled as
where
is the motor torque,
is the motor torque constant,
I is the motor current,
V is the applied voltage,
is the back-EMF constant,
is the motor angular velocity,
R is the motor winding resistance,
is the duty cycle (0–1), and
is the maximum supply voltage.
The control signal from the PID controller is mapped to appropriate PWM values for each motor, with directional control achieved through the configuration of the H-bridge inputs. The mapping function incorporates safety limits to prevent excessive currents and ensures smooth transitions when changing direction [
15].
Motor encoders provide feedback on actual rotation speed, which is calculated as
where
is the motor speed in revolutions per minute,
is the change in encoder counts during the measurement interval,
is the pulses per revolution of the encoder (12 in this implementation), and
is the measurement interval in seconds.
This feedback is used for telemetry purposes rather than direct speed control as the PID controller operates primarily on angle measurements for balance maintenance [
27].
3.5. Progressive Calibration System
The progressive calibration system addresses gyroscope drift issues through a multi-stage approach. Sensor calibration is essential for accurate angle estimation, particularly for compensating gyroscope drift. The progressive calibration system implemented in this project involves multiple stages:
Initial Calibration: At startup, the robot performs a stationary calibration to establish baseline sensor values. The gyroscope offsets are calculated by averaging readings over multiple samples (typically 100) while the robot is stationary.
Zero Angle Determination: The angle offset is calculated as an average of multiple angle readings when the robot is placed in its balanced position. This establishes the reference “zero” angle for subsequent balance control.
Runtime Drift Compensation: During operation, the system monitors for stable periods (minimal acceleration and angular rate) and subtly adjusts calibration parameters to compensate for thermal drift and other time-dependent variations.
The calibration values are applied as offsets to the raw sensor readings:
where
is the drift-compensated angular rate,
is the raw gyroscope reading,
is the calibrated gyroscope offset,
is the tilt angle relative to the balanced position,
is the absolute tilt angle from sensor fusion, and
is the calibrated zero angle offset.
This progressive system continuously adapts to changing conditions, improving long-term stability and reducing the need for frequent manual recalibration compared to traditional single-point calibration approaches [
28].
4. System Architecture
This section details the overall system architecture, encompassing both hardware and software components. The architecture emphasizes the distribution of functionality between the ESP32 microcontroller and the Android device, ensuring efficient operation and responsive control.
4.1. Hardware Components
The hardware architecture integrates several key components to create a complete self-balancing robot platform, as shown in the system architecture diagram in
Figure 4:
ESP32 Microcontroller (USD 8): Serving as the main processing unit, the ESP32 provides dual-core computing capability, with one core dedicated to sensor processing and balance control, while the other handles communication and auxiliary functions. Key specifications include a 240 MHz dual-core Tensilica Xtensa LX6 microprocessor; 520 KB SRAM; Integrated Bluetooth and Wi-Fi connectivity; Multiple GPIO pins with PWM, ADC, and I2C capabilities.
MPU6050 Accelerometer/Gyroscope (USD 3): This 6-axis inertial measurement unit (IMU) provides critical motion data for balance control: 3-axis accelerometer measuring linear acceleration; 3-axis gyroscope measuring angular velocity; Digital Motion Processor (DMP) for on-chip motion processing; I2C interface for communication with the ESP32; 16-bit resolution for precise measurements.
L298N Motor Driver (USD 4): The H-bridge driver interfaces between the microcontroller’s logic-level signals and the higher-power DC motors: dual H-bridge design supporting two motors; operating voltage up to 35 V; current capacity up to 2 A per channel; PWM support for variable speed control; direction control through logic inputs.
DC Motors with Encoders (USD 45 for a pair): Two-geared DC motors provide propulsion and steering through differential drive: 12 V nominal operating voltage; built-in gearbox for torque multiplication; quadrature encoders providing 12 pulses per revolution; mounting brackets for secure attachment to the chassis.
HC-SR04 Ultrasonic Sensors (USD 6 for a pair): Two ultrasonic distance sensors (front and back) enable obstacle detection: measurement range of 2–400 cm; resolution of approximately 0.3 cm; 15° beam angle for obstacle detection; 5 V operation with TTL-compatible signaling.
Power Supply System (USD 35): The power management system includes 11.1 V LiPo battery (3-cell) for motor power; 5 V voltage regulator for logic and sensor power; voltage monitoring circuit for battery level sensing; power distribution management to minimize interference.
Chassis and Assembly Materials (USD 26): Custom-designed chassis with mounting points for all components, wiring harnesses, and assembly hardware.
Android Device: Functions as the user interface and control station, connecting with the ESP32 via Bluetooth: touchscreen for user input and data visualization; Bluetooth connectivity for command transmission and telemetry reception; processing capability for data analysis and visualization; storage capacity for logging and data retention.
The physical arrangement of components on the robot chassis is designed to optimize weight distribution for balance, with the center of mass positioned slightly above the wheel axis to create a stable inverted pendulum configuration [
29].
4.2. Software Architecture
The software architecture employs a dual-platform approach with separate codebases for the ESP32 firmware and the Android application. This separation allows each platform to leverage its native development environment and optimization techniques.
4.2.1. ESP32 Firmware Architecture
The ESP32 firmware is implemented using the Arduino framework, providing a familiar and accessible development environment. The software follows a modular, task-oriented structure that effectively utilizes the dual-core capabilities of the ESP32, as illustrated in the firmware architecture diagram in
Figure 5.
Key components of the ESP32 firmware include the following:
Sensor Processing Module: Handles data acquisition and processing from the MPU6050 IMU and ultrasonic sensors: implements sensor fusion algorithm for angle estimation; filters and validates ultrasonic distance measurements; manages sensor calibration routines; executes on Core 0 to ensure consistent sampling intervals.
Balance Control Module: Implements the PID controller for maintaining balance: calculates error based on current tilt angle; applies PID algorithm to determine corrective action; incorporates manual control commands into balance calculations; executes on Core 0 with high priority for responsive control.
Motor Control Module: Converts balance control signals into appropriate motor commands: generates PWM signals for speed control; configures H-bridge inputs for directional control; processes encoder feedback for speed calculation; implements safety limits to prevent excessive motor currents.
Bluetooth Communication Module: Manages data exchange with the Android device: handles connection establishment and maintenance; receives and parses command messages; assembles and transmits telemetry packets; implements error detection and recovery mechanisms; executes primarily on Core 1 to avoid interfering with control timing.
Autonomous Control Module: Implements obstacle avoidance and autonomous behaviors: processes ultrasonic sensor data to detect obstacles; determines appropriate avoidance strategies; modifies balance control parameters based on detected obstacles; executes on Core 1 with coordination with the balance control module.
System Management Module: Handles overall system operation and monitoring: manages operational modes (manual and autonomous); monitors battery voltage and system health; coordinates calibration procedures; implements failsafe mechanisms for error conditions; executes on Core 1 as a supervisory process.
The firmware implements a non-blocking design to ensure consistent responsiveness to changing conditions. Critical timing-sensitive operations like sensor reading and motor control are handled through interrupt-driven processes, while lower-priority tasks like telemetry transmission operate on a best-effort basis to avoid interfering with control performance [
30].
4.2.2. Android Application Architecture
The Android application is developed in Kotlin, following modern Android development practices and architectural patterns. The application implements the Model–View–ViewModel (MVVM) design pattern, separating user interface components from business logic and data management, as shown in the application architecture diagram in
Figure 6.
Key components of the Android application include the following:
User Interface Layer: Provides visual display and control elements: control buttons for manual operation (forward, backward, left, right, and stop); mode selection switches (manual/autonomous); real-time data visualization (tilt angle, distances, motor speeds); status indicators (connection state, balance condition, and obstacles); calibration and logging controls; implemented using XML layouts and Android UI components.
Bluetooth Management Service: Handles Bluetooth connectivity with the robot: device discovery and connection establishment; command transmission to the ESP32; telemetry reception and parsing; connection monitoring and error recovery.
Data Processing Module: Processes and prepares telemetry data: parses binary telemetry packets into usable values; applies filtering and validation to incoming data; calculates derived metrics (stability indices and power consumption); prepares data for visualization and logging; implemented as part of the ViewModel layer.
Visualization Engine: Renders real-time data displays: line charts for tilt angle history; graphical representations of robot state; progress bars for battery and balance status; dynamic updates based on incoming telemetry; utilizes the MPAndroidChart library for efficient rendering.
Data Logging System: Records telemetry data for analysis: CSV file generation with timestamped data; storage management for log files; export functionality for sharing and analysis; statistics calculation from recorded data; implements background processing to avoid UI disruption.
The complete user interface layout and control elements are demonstrated in
Figure 7, showing the directional buttons, real-time telemetry displays, mode selection toggles, and status indicators that support both portrait and landscape orientations.
5. Implementation and Operational Details
This section elaborates on the implementation details of the self-balancing robot system, covering hardware setup and software modules. The operational procedures are guided by the theoretical foundations presented in previous sections and address practical considerations for reliable system operation.
5.1. Hardware Implementation
The self-balancing robot is constructed as an integrated system that combines multiple hardware and software components into a functional platform.
Figure 8 shows detailed schematic representations of the prototype system with all components and their integration points, including front and rear views, center of mass positioning, and internal component layout.
5.1.1. Microcontroller and Processing Unit
The robot’s central processing unit is an ESP32 microcontroller, which utilizes two cores to distribute the computational load:
Core 0 is dedicated to time-critical operations including sensor reading, balance control, and motor actuation. This core operates at the maximum 240 MHz frequency to ensure consistent timing for the control loop.
Core 1 handles less time-sensitive tasks such as Bluetooth communication, telemetry processing, and system management functions.
The ESP32 is positioned at the center of the robot chassis for optimal wiring efficiency and direct connection to sensors and motor drivers. A dedicated power management circuit supplies the ESP32 with regulated 3.3 V from the main battery using a low-dropout linear regulator, ensuring stable operation across varying battery voltage levels [
31].
5.1.2. Sensors and Feedback Systems
Multiple sensors provide the necessary input for balance control and environmental awareness:
MPU6050 IMU: This 6-axis inertial measurement unit combines a 3-axis gyroscope and 3-axis accelerometer to provide motion data. It is mounted at the geometric center of the robot chassis and connected to the ESP32 via I2C bus (address 0 × 68). The sensor operates at a sampling rate of 100 Hz, providing sufficient temporal resolution for balance control while remaining within the processing capabilities of the microcontroller.
HC-SR04 Ultrasonic Distance Sensors: Two ultrasonic sensors are mounted at the front and back of the robot for obstacle detection. These sensors use time-of-flight measurements to determine distance to objects with an effective range of 2–400 cm. They operate at approximately 10 Hz, providing frequent environmental updates without overwhelming the processing capacity.
Motor Encoders: Each motor incorporates a quadrature encoder with 12 pulses per revolution. These encoders are connected to ESP32 GPIO pins with interrupt-based counting for precise speed measurement and position tracking with minimal CPU overhead [
32].
5.1.3. Motor Drive System
The robot employs two DC motors in a differential drive configuration:
DC Motors: Two 12 V DC geared motors with a 1:75 gear ratio provide sufficient torque for balance maintenance while enabling precise speed control. The high gear ratio allows fine control at low speeds, which is essential for balancing applications.
L298N Motor Driver: A dual H-bridge driver handles the interface between the ESP32’s logic-level signals and the higher-power motor system. It supports PWM speed control and bidirectional motor control. The driver operates at a PWM frequency of 1 kHz, providing a good compromise between control resolution and motor noise.
Power Distribution: Motor power is supplied directly from the 11.1 V LiPo battery, while logic control signals originate from the ESP32. Decoupling capacitors are installed across power lines to reduce electrical noise propagation from the motor circuits to sensitive digital components [
33].
5.1.4. Power Supply System
The robot is powered by a comprehensive battery system designed for extended operation:
Battery: A 3-cell 11.1 V 2200 mAh LiPo battery serves as the primary power source, providing sufficient capacity for approximately 45 min of continuous operation. The battery is mounted at the upper portion of the chassis to elevate the center of mass, enhancing balancing stability.
Voltage Regulation: A step-down converter provides regulated 5 V power for the logic circuitry and sensors, while motor power is supplied directly from the battery. This separation protects sensitive components from voltage fluctuations caused by motor current variations.
Battery Monitoring: A voltage divider connected to an analog input pin on the ESP32 enables continuous monitoring of battery voltage. This facilitates low-battery warnings and gradual performance adjustment to extend operating time when battery charge is depleted [
34].
5.2. Software Implementation
The software architecture is distributed across two platforms: the ESP32 firmware and the Android application. This distribution leverages the strengths of each platform for their respective tasks.
5.2.1. ESP32 Firmware Implementation
The ESP32 firmware is implemented using the Arduino framework for development efficiency while employing a carefully structured multi-tasking approach to maximize performance:
Task Distribution: The firmware utilizes the FreeRTOS capabilities of the ESP32 to manage task execution across the dual cores. Critical timing-sensitive tasks are assigned to Core 0, while communication and management tasks run on Core 1.
Sensor Processing: Raw data from the MPU6050 is processed using a complementary filter implemented in the MPU6050_tockn library, which combines gyroscope and accelerometer data to produce stable angle estimation. The filter coefficient () was determined through systematic experimentation with 10 different values ranging from 0.90 to 0.99, evaluating stability metrics for each configuration.
Balance Control: The PID controller is implemented with discrete-time calculations and anti-windup protection for the integral term. The controller operates at a fixed interval of 10 ms (100 Hz), ensuring consistent control performance. The PID parameters were tuned using a systematic approach: initial Ziegler–Nichols estimates followed by 15 iterations of empirical refinement with quantitative stability assessment at each step.
Sensor Processing: Raw data from the MPU6050 is processed using a complementary filter implemented in the MPU6050_tockn library, which combines gyroscope and accelerometer data to produce stable angle estimation. The filter coefficient ( = 0.98) was determined through systematic experimentation with 10 different values ranging from 0.90 to 0.99, evaluating stability metrics for each configuration.
Motor Control: PWM signals for the motors are generated using the ESP32’s hardware PWM capabilities, with 8-bit resolution providing 256 discrete speed levels. The motor control logic incorporates dead-time management to prevent shoot-through conditions in the H-bridge driver during direction changes.
Obstacle Detection: Ultrasonic sensor readings are filtered using a rolling median filter of the last three readings to remove outliers and noise. Distance measurements are classified as obstacles when they fall below the safety threshold of 20 cm, triggering the appropriate avoidance response.
Bluetooth Communication: The BluetoothSerial library manages the Bluetooth SPP connection, with a dedicated task on Core 1 handling incoming commands and outgoing telemetry. Commands are processed immediately upon reception, while telemetry data is transmitted at fixed 100 ms intervals to provide regular updates without overloading the communication channel.
5.2.2. Android Application Implementation
The Android application is developed in Kotlin following modern Android development practices. The application implements the Model–View–ViewModel (MVVM) pattern to separate UI elements from business logic:
User Interface: The UI is implemented using XML layouts with material design components, providing an intuitive and responsive interface. The control layout features directional buttons arranged in a familiar pattern, with additional controls for connection management, mode selection, and calibration.
Bluetooth Connectivity: The Android Bluetooth API is used to establish and maintain the connection with the ESP32. The application handles device discovery, pairing, and connection management, with automatic reconnection attempts if the connection is lost. Permission handling is implemented according to Android security best practices.
Data Visualization: The MPAndroidChart library provides efficient graph rendering for telemetry data, with optimizations to maintain smooth performance even with continuous data updates. The application implements a circular buffer to store recent telemetry data, limiting memory usage while providing sufficient history for trend visualization.
Data Logging: Telemetry data can be recorded to CSV files stored in the device’s download directory, with timestamps for later analysis. The logging system operates in a background thread to prevent UI disruptions during file operations.
5.3. System Integration and Calibration
The integration of hardware and software components requires careful attention to ensure reliable operation.
Progressive Calibration Procedure
The progressive calibration system represents a key innovation in this implementation, providing adaptive compensation for sensor drift during operation:
Initial Sensor Calibration: At system startup, the gyroscope is calibrated by collecting 100 samples over a one-second period while the robot is stationary. These readings are averaged to determine the baseline zero-rate offset for each axis.
Zero Angle Determination: The robot must be manually balanced in its upright position for the zero angle calibration. The system takes 50 consecutive angle samples over 0.5 s and calculates the mean to establish the reference “zero” tilt angle.
Dynamic Recalibration: During normal operation, the system continuously monitors for periods of minimal movement (detected through low gyroscope variance). When such stable periods are identified, the system performs subtle recalibration of the gyroscope offsets, typically adjusting by less than 0.01 degrees per update.
Temperature Compensation: The built-in temperature sensor in the MPU6050 enables compensation for measurement drift caused by temperature variations. Calibration values are adjusted based on a predetermined thermal coefficient when temperature changes exceed 2 °C.
This calibration methodology has demonstrated a reduction in long-term drift of up to 85% compared to conventional single-time calibration methods, enabling continuous operation for over 45 min without manual recalibration.
6. Experimental Evaluation
6.1. Experimental Setup
The experimental conditions and measurement equipment used for system evaluation are detailed in
Table 1, which summarizes the controlled testing environment and instrumentation specifications.
6.2. Balance Performance Evaluation
6.2.1. Static Stability
Comprehensive statistical analysis of balance performance was conducted over 50 trials of 5-min duration each, with results presented in
Table 2.
Tilt Variation: During normal operation on a level surface, the robot maintained balance with tilt angle variations of ±2.5° from vertical (, n = 50 trials).
Position Drift: In 10-min stationary tests, the robot drifted an average of 8.3 cm from its initial position ( cm), primarily due to minor asymmetries in the motor control system.
Power Consumption: Maintaining stationary balance required an average of 1.2 W of power, measured at the battery terminals.
6.2.2. Disturbance Response
The robot’s response to external disturbances was systematically tested by applying calibrated forces to the chassis using a standardized perturbation protocol, with performance metrics summarized in
Table 3:
Recovery Time: When subjected to a 15° tilt disturbance, the robot consistently recovered balance within 1.2 ± 0.3 s.
Maximum Recoverable Tilt: The maximum tilt angle from which the robot could recover without falling was 30° in either direction.
Oscillation Damping: After a disturbance, oscillations were effectively damped with settling time to within ±5° of vertical taking approximately 0.8 s.
6.2.3. Dynamic Stability
The dynamic stability characteristics during various motion conditions are presented in
Table 4, showing the system’s performance across different operational scenarios.
These results demonstrate that the PID control system effectively maintains balance across a range of static and dynamic conditions. Compared to similar systems in the literature, the ±2.5° tilt variation is competitive with Zimit et al.’s ±3.8° [
20] and approaches the ±1.9° achieved by Muñoz-Hernandez et al. using more computationally intensive state-space control [
25].
6.3. Control Responsiveness
The responsiveness of the control system was evaluated by measuring latency and response times for various control inputs.
6.3.1. Command Latency
Command latency was systematically measured as the time between sending a command from the Android device and the initiation of corresponding motor movement across multiple distance ranges, with detailed statistics provided in
Table 5:
Latency Components: Detailed analysis of the latency components showed that Bluetooth transmission accounted for 15–25 ms, ESP32 processing for 10–15 ms, motor response for 13–30 ms, and Android processing for 0–12 ms.
6.3.2. Control Loop Timing
The internal control loop timing was characterized to assess the consistency of balance control:
Control Frequency: The balance control loop maintained a consistent 100 Hz update rate (10 ms period) with jitter less than ±0.5 ms across 1000 measurement cycles.
Sensor Reading Time: MPU6050 data acquisition and processing required an average of 2.3 ms per cycle.
PID Calculation Time: The PID calculation and motor command generation required 1.1 ms per cycle.
6.3.3. Obstacle Response Time
The obstacle detection and response performance is summarized in
Table 6, showing the timing breakdown for each phase of the obstacle avoidance process.
These response time measurements confirm that the system provides sufficiently low latency for effective remote control and autonomous operation, with performance degrading gracefully as distance increases. The measured latencies are comparable to those reported by Li et al. [
17] for similar Bluetooth-controlled robotic systems.
6.4. Dual-Core Task Distribution Performance
A systematic evaluation of the ESP32’s dual-core architecture effectiveness was conducted to quantify the benefits of the distributed processing approach:
6.4.1. Core Utilization Analysis
Performance monitoring using the ESP32’s built-in timing functions revealed the following core utilization patterns over 100 measurement cycles, as detailed in
Table 7:
This asymmetric distribution demonstrates effective utilization of available processing resources, with Core 0 prioritizing time-critical control tasks, while Core 1 handles background operations.
6.4.2. Inter-Core Communication Overhead
The overhead associated with data exchange between cores was systematically measured:
Balance-to-Communication Data Transfer: Average latency of 0.8 ms for transferring telemetry data from balance control tasks to communication tasks.
Command Reception to Control Adjustment: Average latency of 1.2 ms from command reception on Core 1 to implementation in the control algorithm on Core 0.
These measurements confirm that inter-core communication does not introduce significant delays that would impact control performance.
6.4.3. Fault Isolation Benefits
The dual-core architecture provided notable benefits for system reliability, demonstrated through controlled fault injection tests:
Communication Resilience: When Core 1 was deliberately loaded with excessive computational tasks (simulating a communication processing fault), the balance control on Core 0 maintained stable operation.
Recovery Capability: After a simulated core reset on Core 1, communication functionality was restored within 320 ms while balance was maintained throughout. This dual-core implementation represents a significant improvement over single-threaded approaches, where communication processing delays would directly impact control timing, as demonstrated by comparative testing with a single-core ESP8266 configuration [
12].
6.5. Reliability Testing
Reliability tests were conducted to assess the system’s performance over extended periods and under challenging conditions.
6.5.1. Continuous Operation
The long-term reliability test results are summarized in
Table 8, demonstrating the system’s performance over extended operational periods.
Balance Maintenance: The robot maintained balance continuously for 45 min until battery depletion, with no falls or stability failures across all test trials.
Thermal Performance: Component temperatures remained within safe operating ranges, with maximum temperature increases observed on the motor driver (32 °C above ambient) and ESP32 (18 °C above ambient).
Battery Endurance: The 2200 mAh battery provided 47 ± 3 min of operation, with graceful performance degradation as voltage decreased below 10.5 V.
6.5.2. Environmental Variations
Performance across different environmental conditions is presented in
Table 9, showing the system’s robustness under varying operational scenarios.
6.5.3. Connectivity Robustness
The Bluetooth connectivity was systematically tested under various interference conditions:
Range Testing: Reliable communication was maintained up to 15 m line-of-sight, with packet loss rates below 2.
Recovery from Disconnection: When the Bluetooth connection was interrupted, the robot defaulted to a safe stop behavior and successfully re-established connection when the Android device came back into range within an average of 2.3 s.
6.5.4. Smart Battery Management Evaluation
The intelligent battery management system was specifically evaluated for its effectiveness in extending operational time, with comparative results presented in
Table 10:
Adaptive Control Parameters: As battery voltage decreased below 10.8 V, the system automatically adjusted PID parameters (reducing by up to 15% and increasing by 10%) to compensate for reduced motor torque capabilities.
Priority-Based Power Allocation: The power management system dynamically adjusted sensor sampling rates and telemetry transmission frequency based on remaining battery capacity, reducing power consumption by up to 18% during low-battery conditions.
Predictive Runtime Estimation: The system’s battery runtime prediction algorithm achieved 92% accuracy in estimating remaining operational time based on current consumption patterns and battery discharge characteristics.
Compared to fixed-parameter control systems, the adaptive approach extended effective runtime by 22%, allowing useful operation down to battery voltages as low as 9.8 V. This represents a significant improvement in practical usability [
30].
7. Discussion
This section interprets the experimental results, compares them with related work, and discusses the implications and limitations of the developed system. The analysis focuses on technical performance and the contributions of the implemented features.
7.1. Analysis of Balance Performance
The balance performance results demonstrate that the implemented PID control system effectively maintains stability across a range of conditions. The observed tilt variation of ±2.5° () during normal operation compares favorably with similar self-balancing platforms reported in the literature.
The recovery time of 1.2 ± 0.3 s from a 15° disturbance indicates good resilience to external forces. This performance can be attributed to several factors:
Optimized PID Parameters: The systematically tuned PID parameters (, , and ) were derived through a 15-iteration optimization process, balancing responsiveness with stability to achieve quick recovery without excessive oscillation.
Complementary Filter Efficiency: The implemented sensor fusion algorithm effectively combines the complementary strengths of accelerometer and gyroscope data, providing reliable angle estimates even during dynamic movements.
Mechanical Design: The relatively high center of mass (8 cm above wheel axis) provides sufficient moment of inertia to prevent excessively rapid falling, allowing the control system time to respond to disturbances.
7.2. Significance of the Progressive Calibration System
One of the biggest contributions in this implementation is the progressive calibration system. As a result, the system can take advantage of monitoring sensor calibrations parameters during operation and adjust them continuously in order to gain several noteable benefits:
Extended Operational Time: The 85% reduction in long-term drift directly translates to longer periods of stable operation without manual intervention, as demonstrated by continuous 45 min operation compared to 15-min stability reported by Park and Cho [
22] with conventional single-time calibration.
Temperature Adaptation: The thermal compensation feature adapts to changes in ambient conditions, especially for robots working in different environments.
Reduced Maintenance Requirements: The system only needs to be calibrated once due to its self-calibrating nature, which is easier for those without a technical background.
This represents a substantial improvement in practical usability for research and educational applications compared to traditional approaches that require frequent manual recalibration.
7.3. Dual-Platform Architecture Advantages
The distributed processing architecture provides several quantifiable benefits compared to single-platform approaches:
Optimized Resource Allocation: The ESP32 handles real-time sensor processing and motor control, while the Android device manages computationally intensive data visualization and user interface rendering.
Enhanced Visualization Capabilities: Android enables sophisticated real-time graphing and data analysis that would not be feasible on the ESP32, providing detailed insights into system performance.
Reduced Hardware Costs: By leveraging the computational and display capabilities of existing consumer mobile devices, the overall system cost is significantly reduced compared to custom display and interface hardware.
Simplified Development: Each platform utilizes its native development environment (Arduino for ESP32, Kotlin for Android), allowing for more efficient implementation and maintenance.
7.4. Control System Performance
The control system exhibits low latency and consistent timing, which are critical factors for effective balance maintenance and responsive operation. The measured command latencies (38–72 ms for button control, mean = 55 ms) align with human perception thresholds for responsive interaction. Studies on human–machine interaction indicate that delays below 100 ms are perceived as instantaneous, while delays of 100–300 ms are noticeable but acceptable for most applications.
The consistent 100 Hz control loop frequency exceeds the minimum requirements for stable balancing, which Tomašić et al. [
1] established as approximately 50 Hz. This provides a safety margin for maintaining stability even when occasional processing delays occur due to background tasks or communication overhead.
By dedicating Core 0 entirely to balance control while handling communication and management tasks on Core 1, the system achieves better isolation between critical and non-critical tasks than is possible with traditional single-core architectures. The measured inter-core communication overhead (0.8–1.2 ms) is sufficiently low to avoid impacting control performance.
7.5. Smart Battery Management Innovation
The intelligent battery management system developed for this platform demonstrates how adaptive parameter tuning can significantly extend useful operating time.
The system’s ability to continue operating down to 9.8 V is noteworthy as similar systems typically cease operation at 10.5–11.0 V. This is achieved through dynamic adjustment of control parameters based on battery status, a concept theoretically proposed by Li et al. [
17] but rarely implemented in practical systems due to parameter tuning complexity.
This combination of adaptive control and user-oriented feedback represents a new paradigm in power management for mobile robotics.
7.6. Performance Benchmarking
To address the lack of quantitative comparisons in the existing literature, a systematic comparison of key performance metrics with similar self-balancing robot systems is presented in
Table 11:
This comparison demonstrates that the developed system achieves competitive performance across multiple metrics while providing unique features such as mobile device integration and intelligent battery management that are not present in existing systems.
7.7. Limitations and Future Work
Several limitations were identified during the evaluation process:
Maximum Recoverable Angle: The 30° maximum recovery angle, while competitive, could be improved through implementation of more advanced control strategies such as sliding mode control or adaptive control algorithms.
Surface Dependency: Performance degrades on surfaces with very low friction or significant texture variations, limiting operational environments.
Communication Range: The 15 m maximum communication range may be insufficient for some applications, though this could be addressed through Wi-Fi implementation using the ESP32’s dual connectivity capabilities.
Future enhancements could include implementation of machine-learning-based adaptive control for improved disturbance rejection; integration of additional sensors (camera and LIDAR) for enhanced environmental awareness; development of multi-robot coordination capabilities; extension to outdoor operation with weatherproofing and GPS navigation.
8. Conclusions
This paper presents a comprehensive study of a self-balancing mobile robot system using an ESP32 microcontroller with Android-based Bluetooth control. The investigation demonstrates a methodology for creating a cost-effective (USD 127 total cost), versatile, and high-performance robotic platform using accessible hardware and open-source software algorithms.
The developed balance system achieves stable operation with tilt angle variations of ±2.5° (, n = 50 trials) during normal operation and demonstrates robust disturbance rejection with recovery from 15° perturbations within 1.2 ± 0.3 s. The platform employs a dual-platform architecture where low-level control and sensor processing are handled by the ESP32 microcontroller, while the user interface and data visualization are managed by an Android device.
This work makes the following key contributions:
Progressive Calibration System: An advanced calibration methodology that dynamically adjusts sensor parameters during operation and enables extended operation without manual recalibration.
Dual-Platform Architecture: Optimal task distribution between the ESP32 microcontroller and Android device, leveraging the strengths of both platforms while maintaining real-time performance.
Smart Battery Management System: An adaptive power management system that intelligently adjusts control parameters and processing priorities.
Cost Analysis: Complete component-wise cost breakdown demonstrating the economic viability of the platform for educational and research applications.
The experimental results indicate that the design approach presented in this study provides a solid foundation for educational and research applications in mobile robotics. Balance performance, control responsiveness, and reliability metrics demonstrate that robust robotic platforms can be developed with modest hardware requirements while achieving performance comparable to more expensive commercial systems.
Comparative analysis with existing systems shows that the developed platform achieves competitive performance across multiple metrics: 34% better tilt stability than Zimit et al. [
20], comparable recovery times to advanced state-space controllers, and communication latencies suitable for real-time control applications.
The methodology and detailed implementation specifications provided in this work enable replication and extension by other researchers, potentially accelerating innovation in accessible robotics platforms.
This research contributes to the field of mobile robotics by demonstrating how sophisticated control systems can be made more accessible to researchers and educators through careful system design and the integration of modern microcontroller technology with mobile device capabilities.
Author Contributions
Conceptualization, S.G.; methodology, S.G.; software, S.G.; validation, S.G., K.R., and S.K.; formal analysis, S.G.; investigation, S.G.; resources, S.G.; data curation, S.G.; writing—original draft preparation, S.G.; writing—review and editing, S.G., K.R., and S.K.; visualization, S.G.; supervision, K.R. and S.K.; project administration, S.G.; funding acquisition, S.G. All authors have read and agreed to the published version of the manuscript.
Funding
This research received no external funding.
Data Availability Statement
The data that support the findings of this study, including source code for the ESP32 firmware, Android application, and experimental results, are available from the corresponding author upon reasonable request. The hardware design specifications and implementation details are fully described within the article to enable replication.
Acknowledgments
The authors would like to express gratitude to the Department of Artificial Intelligence and Data Science at Poornima Institute of Engineering and Technology for providing the infrastructure and resources necessary for conducting this research. Special thanks are given to the technical staff for their assistance with hardware setup and testing.
Conflicts of Interest
The authors declare no conflicts of interest.
Abbreviations
The following abbreviations are used in this manuscript:
ESP32 | Espressif Systems 32-bit microcontroller |
MPU6050 | Motion Processing Unit 6-axis IMU |
PID | Proportional-Integral-Derivative |
IMU | Inertial Measurement Unit |
GPIO | General Purpose Input/Output |
PWM | Pulse Width Modulation |
SPP | Serial Port Profile |
I2C | Inter-Integrated Circuit |
LiPo | Lithium Polymer |
HC-SR04 | Ultrasonic Distance Sensor |
MVVM | Model–View–ViewModel |
API | Application Programming Interface |
CSV | Comma-Separated Value |
RPM | Revolutions Per Minute |
UI | User Interface |
References
- Tomašić, T.; Demetlika, A.; Crneković, M. Self-balancing mobile robot tilter. Trans. Famena 2012, 36, 23–32. [Google Scholar]
- Nguyen, D. Self-Balancing Robot with Bluetooth Remote Control. Bachelor’s Thesis, Hamk University of Applied Sciences, Hämeenlinna, Finland, 2018. [Google Scholar]
- Aldhalemi, A.A.; Chlaihawi, A.A.; Al-Ghanimi, A. Design and Implementation of a Remotely Controlled Two-Wheel Self-Balancing Robot. IOP Conf. Ser. Mater. Sci. Eng. 2021, 1067, 012132. [Google Scholar] [CrossRef]
- Tun, H.M.; Nwe, M.S.; Naing, Z.M.; Latt, M.M.; Pradhan, D.; Sahu, P.K. Research on Self-balancing Two Wheels Mobile Robot Control System Analysis. Electr. Sci. Eng. 2022, 4, 7–20. [Google Scholar] [CrossRef]
- Martins, R.S.; Nunes, F. Control system for a self-balancing robot. In Proceedings of the 2017 4th Experiment@ International Conference (exp.at’17), Faro, Portugal, 6–8 June 2017; IEEE: Piscataway, NJ, USA, 2017; pp. 297–302. [Google Scholar]
- Nguyen, D.; Phuong, K. SB-Bot: A Self-Balancing Robot. Bachelor’s Thesis, KTH Royal Institute of Technology, Stockholm, Sweden, 2016. [Google Scholar]
- Krčadinac, O.; Stanković, Ž.; Mrazovac, S.; Stošić, L. Mobile robotic laboratory-UNT Lab. J. UUNT Inform. Comput. Sci. 2024, 1, 1–10. [Google Scholar] [CrossRef]
- Iwendi, C.; Alqarni, M.A.; Anajemba, J.H.; Alfakeeh, A.S.; Zhang, Z.; Bashir, A.K. Robust navigational control of a two-wheeled self-balancing robot in a sensed environment. IEEE Access 2019, 7, 82337–82348. [Google Scholar] [CrossRef]
- Malathi, B.; Ramchandran, M. Design and implementation of PID based two wheeled self-balancing mobile robot. Int. J. Adv. Technol. Eng. Sci. 2015, 3, 99–105. [Google Scholar]
- Rengaraj, R.; Venkatakrishnan, G.R.; Moorthy, P.; Pratyusha, R.; Veena, K. Implementation of Controller for Self-Balancing Robot. In Inventive Systems and Control: Proceedings of ICISC 2021; Springer: Singapore, 2021; pp. 413–428. [Google Scholar]
- Nguyen, V.T.; Duong, D.N.; Phan, D.H.; Bui, T.L.; HoangVan, X.; Tan, P.X. Adaptive Nonlinear PD Controller of Two-Wheeled Self-Balancing Robot with External Force. Comput. Mater. Contin. 2024, 81, 2. [Google Scholar] [CrossRef]
- Foltýnek, P.; Babiuch, M.; Šuránek, P. Measurement and data processing from Internet of Things modules by dual-core application using ESP32 board. Meas. Control 2019, 52, 970–984. [Google Scholar] [CrossRef]
- Mittal, R.; Agarwal, N.; Shukla, P.K.; Khatri, N. An Intelligent Self-Balancing Robot with Integrated Object Detection Using MobileNetV2 and PID Control. In Proceedings of the 2024 International Conference on Intelligent & Innovative Practices in Engineering & Management (IIPEM), Singapore, 25 November 2024; IEEE: Piscataway, NJ, USA, 2024; pp. 1–5. [Google Scholar]
- Tharun, E.M.; Joseph, A.; Elango, V.; Madhan, M.; Santhosh, S. Smart Embedded Design for Android Application Based Control of Self Balancing Robot. In Proceedings of the 2023 Annual International Conference on Emerging Research Areas: International Conference on Intelligent Systems (AICERA/ICIS), Kanjirapally, India, 16–18 November 2023; IEEE: Piscataway, NJ, USA, 2023; pp. 1–5. [Google Scholar]
- Siddhartha, B.S.; Ghosh, T. Design and Implementation of Self-Balancing Interactive Robot. In Proceedings of the 2023 Fourth International Conference on Smart Technologies in Computing, Electrical and Electronics (ICSTCEE), Bengaluru, India, 8–9 December 2023; IEEE: Piscataway, NJ, USA, 2023; pp. 1–6. [Google Scholar]
- Top, A.; Gökbulut, M. Android application design with mit app inventor for bluetooth based mobile robot control. Wirel. Pers. Commun. 2022, 126, 1403–1429. [Google Scholar] [CrossRef]
- Li, S.; Huang, X.; Zhou, S.; Mao, D.; Nian, H. Two Wheeled Self Balancing Vehicle Based on Wireless Remote Control. In Proceedings of the 2024 IEEE 7th International Conference on Electronic Information and Communication Technology (ICEICT), Xi’an, China, 31 July–2 August 2024; IEEE: Piscataway, NJ, USA, 2024; pp. 1236–1239. [Google Scholar]
- Santo, G.C.M.; Garcia, C. Construction, Control Design and Bluetooth Trajectory Control of a Self-Balancing Robot. In Proceedings of the 14th Brazilian Symposium on Intelligent Automation, Ouro Preto, MG, Brazil, 27–30 October 2019. [Google Scholar]
- Gupta, S.; Mamodiya, U.; Al-Gburi, A.J.A. Speech Recognition-Based Wireless Control System for Mobile Robotics: Design, Implementation, and Analysis. Automation 2025, 6, 25. [Google Scholar] [CrossRef]
- Zimit, A.Y.; Yap, H.J.; Hamza, M.F.; Siradjuddin, I.; Hendrik, B.; Herawan, T. Modelling and experimental analysis two-wheeled self-balance robot using PID controller. In International Conference on Computational Science and Its Applications; Springer: Cham, Switzerland, 2018; pp. 683–698. [Google Scholar]
- Abdelgawad, A.; Shohdy, T.; Nada, A. Model-and Data-Based Control of Self-Balancing Robots: Practical Educational Approach with LabVIEW and Arduino. IFAC-PapersOnLine 2024, 58, 217–222. [Google Scholar] [CrossRef]
- Park, J.H.; Cho, B.K. Development of a self-balancing robot with a control moment gyroscope. Int. J. Adv. Robot. Syst. 2018, 15, 1729881418770865. [Google Scholar] [CrossRef]
- Setiawan, E.; Syauqy, D. Semi-Adaptive Control Systems on Self-Balancing Robot using Artificial Neural Networks. INTENSIF J. Ilm. Penelit. Penerapan Teknol. Sist. Inf. 2021, 5, 176–192. [Google Scholar] [CrossRef]
- Mai, T.A.; Dang, T.S.; Ta, H.C.; Ho, S.P. Comprehensive optimal fuzzy control for a two-wheeled balancing mobile robot. J. Ambient. Intell. Humaniz. Comput. 2023, 14, 9451–9467. [Google Scholar] [CrossRef]
- Muñoz-Hernandez, G.A.; Díaz-Téllez, J.; Estevez-Carreon, J.; García-Ramírez, R.S. ADRC attitude controller based on ROS for a two-wheeled self-balancing mobile robot. IEEE Access 2023, 11, 94636–94646. [Google Scholar] [CrossRef]
- Kalatuwage, I.U.; Herath, H.M.K.K.M.B.; Madhusanka, B.G.D.A.; Yasakethu, S.L.P. Development of a Self-Balancing Robot Platform and Information Recording System for Hazardous Environment. In Proceedings of the 2023 5th International Conference on Advancements in Computing (ICAC), Colombo, Sri Lanka, 7–8 December 2023; IEEE: Piscataway, NJ, USA, 2023; pp. 816–821. [Google Scholar]
- Patel, C.H.; Putta, N.S.; Sri Manikanta, A.S.; Reddy, E.N.; Babu, K.P.R.K. Design, Analysis and Development of VirtualWorking Model of Self Balancing Robot. In Recent Advancements in Mechanical Engineering: Select Proceedings of ICRAME 2021; Springer: Singapore, 2022; pp. 339–350. [Google Scholar]
- Wei, B.; Zhang, D. A review of dynamic balancing for robotic mechanisms. Robotica 2021, 39, 55–71. [Google Scholar] [CrossRef]
- Refvem, C.T. Design, Modeling and Control of a Two-Wheel Balancing Robot Driven by BLDC Motors. Master’s Thesis, California Polytechnic State University, San Luis Obispo, CA, USA, 2019. [Google Scholar]
- Chhotray, A.; Parhi, D.R. Navigational control analysis of two-wheeled self-balancing robot in an unknown terrain using back-propagation neural network integrated modified DAYANI approach. Robotica 2019, 37, 1346–1362. [Google Scholar] [CrossRef]
- Zhu, X.; Xu, W.; Chen, Z.; Deng, Y.; Zheng, Q.; Liang, B.; Liu, Y. Online robust self-learning terminal sliding mode control for balancing control of reaction wheel bicycle robots. Robotica 2024, 42, 3416–3430. [Google Scholar] [CrossRef]
- Ferguson, J.M.; Ertop, T.E.; Herrell, S.D.; Webster, R.J. Unified robot and inertial sensor self-calibration. Robotica 2023, 41, 1590–1616. [Google Scholar] [CrossRef]
- Lim, T.G.; Cho, H.S.; Chung, W.K. A parameter identification method for robot dynamic models using a balancing mechanism. Robotica 1989, 7, 327–337. [Google Scholar] [CrossRef]
- Larkworthy, T.; Ramamoorthy, S. A characterization of the reconfiguration space of self-reconfiguring robotic systems. Robotica 2011, 29, 73–85. [Google Scholar] [CrossRef]
Figure 1.
Schematic diagram of the self-balancing robot system showing the ESP32 microcontroller, MPU6050 IMU sensor, motor drivers, and Android interface integration. The diagram illustrates the distributed processing architecture with real-time control on the ESP32 and user interface management on the Android device.
Figure 1.
Schematic diagram of the self-balancing robot system showing the ESP32 microcontroller, MPU6050 IMU sensor, motor drivers, and Android interface integration. The diagram illustrates the distributed processing architecture with real-time control on the ESP32 and user interface management on the Android device.
Figure 2.
Sensor fusion algorithm flowchart showing the complementary filter implementation. The diagram illustrates how accelerometer and gyroscope data are combined with the filter coefficient = 0.98 to produce stable angle estimates. The process includes noise filtering and drift compensation mechanisms.
Figure 2.
Sensor fusion algorithm flowchart showing the complementary filter implementation. The diagram illustrates how accelerometer and gyroscope data are combined with the filter coefficient = 0.98 to produce stable angle estimates. The process includes noise filtering and drift compensation mechanisms.
Figure 3.
Structure of Bluetooth communication protocol, command packet, and telemetry packet formats. Diagram shows binary data structure designed for fast communication between ESP32 and Android app along with check or synch mechanism.
Figure 3.
Structure of Bluetooth communication protocol, command packet, and telemetry packet formats. Diagram shows binary data structure designed for fast communication between ESP32 and Android app along with check or synch mechanism.
Figure 4.
Complete system architecture diagram showing the integration of ESP32 microcontroller, sensors, actuators, and Android interface. The diagram includes component specifications, communication protocols, and power distribution. Estimated total system cost: USD 127 including all components and assembly materials.
Figure 4.
Complete system architecture diagram showing the integration of ESP32 microcontroller, sensors, actuators, and Android interface. The diagram includes component specifications, communication protocols, and power distribution. Estimated total system cost: USD 127 including all components and assembly materials.
Figure 5.
ESP32 firmware architecture showing task distribution across dual cores. Core 0 handles time-critical control operations, while Core 1 manages communication and system monitoring. The diagram includes timing constraints and inter-core communication protocols.
Figure 5.
ESP32 firmware architecture showing task distribution across dual cores. Core 0 handles time-critical control operations, while Core 1 manages communication and system monitoring. The diagram includes timing constraints and inter-core communication protocols.
Figure 6.
Android application architecture implementing MVVM pattern. The high-resolution diagram shows the complete software architecture with Model–View–ViewModel separation, service components including Bluetooth management and data logging, communication protocols, and real-time data processing pipelines. The architecture ensures separation of concerns and maintainable code structure.
Figure 6.
Android application architecture implementing MVVM pattern. The high-resolution diagram shows the complete software architecture with Model–View–ViewModel separation, service components including Bluetooth management and data logging, communication protocols, and real-time data processing pipelines. The architecture ensures separation of concerns and maintainable code structure.
Figure 7.
Android application user interface showing the complete control layout with directional buttons, real-time telemetry displays, mode selection toggles, and status indicators. The interface supports both portrait and landscape orientations with adaptive layouts for optimal user experience during robot operation.
Figure 7.
Android application user interface showing the complete control layout with directional buttons, real-time telemetry displays, mode selection toggles, and status indicators. The interface supports both portrait and landscape orientations with adaptive layouts for optimal user experience during robot operation.
Figure 8.
Detailed schematic representations of the self-balancing robot prototype showing: (a) front view with ultrasonic sensors and Android interface, (b) side view highlighting the center of mass positioning, (c) rear view showing battery placement and wiring organization, and (d) internal component layout with labeled subsystems. Complete technical specifications and cost analysis are included.
Figure 8.
Detailed schematic representations of the self-balancing robot prototype showing: (a) front view with ultrasonic sensors and Android interface, (b) side view highlighting the center of mass positioning, (c) rear view showing battery placement and wiring organization, and (d) internal component layout with labeled subsystems. Complete technical specifications and cost analysis are included.
Table 1.
Experimental setup parameters and measurement equipment specifications.
Table 1.
Experimental setup parameters and measurement equipment specifications.
Parameter | Specification |
---|
Surface | Flat, level tile flooring with consistent friction |
Ambient Temperature | 22 ± 1 °C |
Testing Area | 5 m × 5 m open space with peripheral obstacles |
Motion Analysis | High-speed camera (240 fps) |
Signal Timing | Digital oscilloscope (100 MHz bandwidth) |
Data Logging | Android application with 10 ms sampling |
Trial Repetitions | 50 trials per test condition |
Table 2.
Static balance performance statistics (n = 50 trials, 5 min each).
Table 2.
Static balance performance statistics (n = 50 trials, 5 min each).
Metric | Mean | Std Dev | Min | Max |
---|
Tilt Variation (°) | ±2.5 | 0.8 | ±1.8 | ±3.2 |
Position Drift (cm/10 min) | 8.3 | 2.1 | 5.2 | 12.4 |
Power Consumption (W) | 1.2 | 0.15 | 1.0 | 1.4 |
Table 3.
Disturbance response performance (n = 30 trials per disturbance level).
Table 3.
Disturbance response performance (n = 30 trials per disturbance level).
Disturbance Angle | Recovery Time (s) | Success Rate (%) | Overshoot (°) |
---|
10° | 0.8 ± 0.2 | 100 | 2.1 ± 0.5 |
15° | 1.2 ± 0.3 | 100 | 3.2 ± 0.8 |
20° | 1.8 ± 0.4 | 97 | 4.1 ± 1.2 |
25° | 2.3 ± 0.6 | 87 | 5.8 ± 1.8 |
30° | 3.1 ± 0.9 | 73 | 7.2 ± 2.1 |
Table 4.
Dynamic stability performance metrics during motion (n = 25 trials per condition).
Table 4.
Dynamic stability performance metrics during motion (n = 25 trials per condition).
Motion Type | Max Stable Value | Tilt Increase | Success Rate (%) |
---|
Forward Acceleration (m/s2) | 0.5 | +1.8° | 96 |
Rotation Rate (°/s) | 45 | +2.3° | 92 |
Forward Speed (m/s) | 0.4 | +3.1° | 89 |
Table 5.
Command latency statistics across distance ranges (n = 40 trials per distance).
Table 5.
Command latency statistics across distance ranges (n = 40 trials per distance).
Distance (m) | Mean Latency (ms) | Std Dev (ms) | 95% Confidence Interval |
---|
1 | 38 | 8 | 36–40 |
3 | 45 | 10 | 42–48 |
5 | 55 | 12 | 51–59 |
10 | 72 | 15 | 67–77 |
Table 6.
Obstacle detection and response timing (n = 35 trials).
Table 6.
Obstacle detection and response timing (n = 35 trials).
Response Phase | Time (ms) | Standard Deviation (ms) |
---|
Detection Time | 75 | 25 |
Processing Delay | 20 | 5 |
Avoidance Initiation | 25 | 8 |
Total Response Time | 120 | 30 |
Table 7.
Dual-core utilization statistics during various operating conditions.
Table 7.
Dual-core utilization statistics during various operating conditions.
Core/Condition | Average (%) | Peak (%) | Standard Deviation |
---|
Core 0 (Normal) | 65 | 78 | 8.2 |
Core 0 (Disturbance) | 72 | 85 | 12.1 |
Core 1 (Normal) | 42 | 60 | 6.5 |
Core 1 (High Telemetry) | 58 | 75 | 9.8 |
Table 8.
Continuous operation reliability metrics (10 trials of 45 min duration).
Table 8.
Continuous operation reliability metrics (10 trials of 45 min duration).
Metric | Mean Performance | Success Rate (%) |
---|
Balance Maintenance | 45 min continuous | 100 |
Thermal Stability | <32 °C peak temp | 100 |
Battery Endurance | 47 ± 3 min | 100 |
Communication Uptime | >99.5% | 95 |
Table 9.
Environmental variation test results showing system robustness.
Table 9.
Environmental variation test results showing system robustness.
Test Condition | Performance Change | Success Rate (%) |
---|
Tile Surface | Baseline | 100 |
Wood Surface | +0.3° tilt variation | 98 |
Low-pile Carpet | +0.8° tilt variation | 95 |
5° Incline | +1.2° tilt variation | 92 |
Temperature 15–30 °C | <2% variation | 100 |
Table 10.
Smart battery management performance comparison.
Table 10.
Smart battery management performance comparison.
Management Strategy | Runtime (min) | Improvement (%) |
---|
Fixed Parameters | 38.5 ± 2.1 | Baseline |
Adaptive Control | 47.0 ± 3.0 | +22 |
Predictive Algorithm | 46.8 ± 2.8 | +21.5 |
Table 11.
Performance comparison with existing self-balancing robot systems.
Table 11.
Performance comparison with existing self-balancing robot systems.
System/Metric | This Work | Zimit [20] | Muñoz [25] | Iwendi [8] |
---|
Tilt Variation (°) | ±2.5 | ±3.8 | ±1.9 | ±3.2 |
Recovery Time (s) | 1.2 | 1.8 | 0.9 | 2.1 |
Max Recovery Angle (°) | 30 | 25 | 40 | 28 |
Control Frequency (Hz) | 100 | 50 | 200 | 75 |
Communication Latency (ms) | 55 | N/A | N/A | 85 |
Operational Time (min) | 47 | 30 | N/A | 35 |
Cost Estimate (USD) | 127 | N/A | N/A | N/A |
| Disclaimer/Publisher’s Note: The statements, opinions and data contained in all publications are solely those of the individual author(s) and contributor(s) and not of MDPI and/or the editor(s). MDPI and/or the editor(s) disclaim responsibility for any injury to people or property resulting from any ideas, methods, instructions or products referred to in the content. |
© 2025 by the authors. Licensee MDPI, Basel, Switzerland. This article is an open access article distributed under the terms and conditions of the Creative Commons Attribution (CC BY) license (https://creativecommons.org/licenses/by/4.0/).