Motion Controlled Robot Car

OVERVIEW

Let's build a futuristic robot toy car that reacts to your hand gestures. Swipe up, down, left, or right to move the car accordingly. With built-in RGB running lights, this interactive project combines motion detection, colorful feedback, and motorized movement to deliver a fun and educational experience.

 

HARDWARE USED

COMPONENTS:

SOFWARE USED

  • Arduino IDE

APPLICATION DISCUSSION

This project introduces gesture recognition, RGB LED control, and motor direction logic. It also improves your embedded systems and circuit prototyping skills. A 4-wheel drive chassis will be used as the base for the project, allowing for smooth movement and precise directional control. The chassis is equipped with four geared DC motors for independent wheel control, providing stability and flexibility in navigating various surfaces. It also offers enough space to mount the microcontroller, sensors, and power supply, making it ideal for prototyping robotics and automation systems.

Let's introduce the different modules and materials used:


CPU: Tensilica Xtensa® dual-core 32-bit LX6, up to 240 MHz
Storage: 448 KB ROM, 520 KB SRAM, 4MB Flash (typical)
I/O PINs: 34 GPIO pins, 18 ADC channels, 2 DAC outputs
Interfaces: 3 SPI, 2 I2C, 2 UART, CAN, IR, PWM, I2S
Connectivity: WiFi 802.11 b/g/n + Bluetooth 4.2 LE
USB: Micro-USB or USB-C (depending on board)
Power Supply: 3.0–3.6V
Software Compatibility: Arduino IDE, MicroPython, ESP-IDF
Dimensions: ~51mm x 25.5mm (varies by board)

ESP32 PIN-OUT
ESP32 Pinout Reference - Last Minute Engineers

 

Functions: Gesture detection, proximity sensing, ambient light, RGB color sensing
Gesture Range:
Up to ~10–15 cm (optimal within 5–10 cm)
Light Sensor:
Red, Green, Blue, and Clear photodiodes
Proximity Sensor:
IR LED with integrated driver
Operating Voltage:
2.4V to 3.6V
Interface:
I2C (400kHz max)
I2C Address:
0x39
Current Consumption:
~1.8mA (gesture mode typical), ultra-low standby current
Gesture Speed:
100–600 mm/s (recommended swipe speed)
Field of View:
~60° for gesture detection
Ambient Light Range:
0.01 lux to 10,000 lux
Dimensions:
3.94 mm × 2.36 mm × 1.35 mm (sensor chip)

 

Type: Common Anode RGB LED
Colors: Red, Green, Blue (can be mixed to form additional colors)
Forward Voltage: Red: 1.8V – 2.2V / Green: 3.0V – 3.4V / Blue: 3.0V – 3.4V
Forward Current: 20mA per color (max continuous)
Recommended Resistors: 220Ω – 330Ω (per channel)
Anode Voltage: Connect common anode to 3.3V or 5V
Control: Via digital GPIO (HIGH = OFF, LOW = ON for common anode)
Dimensions (Typical Module): ~20mm × 15mm

  • RGB PIN-OUT (COMMON ANODE)

Interfacing RGB Led with Arduino | Arduino Project Hub

 

HARDWARE SETUP

Steps in Assembly

1. Prepare your materials(4 wheel car drive motor chassis kit, Breadboard, Rgb module, L298N motor driver, ESP32, and some wires).

 2.  Solder the wires to the motors.

3. Mount the DC motor  onto the chassis and attach the wheels.

4. Flip the chassis over and connect the DC motors to the L298N motor driver.

  • Connect the two left-side motors in series by joining one motor’s positive wire to the other motor’s negative wire. Do the same for the two right-side motors.

  • Then, connect the remaining free wires from each side to the output terminals (OUT1, OUT2 for the left motors and OUT3, OUT4 for the right motors) on the L298N motor driver.

  • Connect the 12V or 7.4V battery pack (depending on your motor voltage rating) to the power terminals (VCC and GND) of the L298N motor driver. Make sure to also connect the 5V ENABLE jumper or wire the 5V OUT pin to supply power to the logic circuits.

  • Double-check the connections to ensure the motors spin in the correct direction later.

5. Connect the input pins of the L298N motor driver to the ESP32.

5. Connect the input pins of the L298N motor driver to the ESP32.

  • Connect the motor driver’s control pins to the ESP32 as follows:

    • IN_A → GPIO 25

    • IN_B → GPIO 26

    • IN_C → GPIO 32

    • IN_D → GPIO 33

6. Add the second layer of the chassis and mount the APDS-9960 motion sensor module.

  • Secure the APDS-9960 module onto the upper layer of the chassis.

  • Connect the module’s VCC pin to the 3.3V supply of the ESP32 and its GND pin to the ESP32’s GND.

  • Connect the SDA pin of the APDS-9960 to GPIO 21 (SDA) on the ESP32 and the SCL pin to GPIO 22 (SCL).

7. Add RGB modules for direction indication (common anode type).

  • Connect the VCC of all RGB modules to the 3.3V power supply on the ESP32.

  • Wire the RGB pins as follows:

    • First RGB module: Red → GPIO 4, Green → GPIO 15, Blue → GPIO 2

    • Second RGB module: Red → GPIO 13, Green → GPIO 23, Blue → GPIO 27

    • Third RGB module: Red → GPIO 28, Green → GPIO 30, Blue → GPIO 31

  • These LEDs will serve as indicators for movement directions.

8. Connect the ESP32 and motor driver to your power supply.

  • In this setup, use a 12V battery pack made of four LiPo batteries in series.

  • Use a buck converter to step down the voltage from 12V to 5V.

  • Before connecting to the ESP32 and motor driver, use a multimeter to test and confirm the voltage output of the buck converter is correctly set to 5V.

  • Connect the buck converter’s 5V output to power both the ESP32 and the 5V pin on the motor driver.

  • Ensure all grounds (battery, buck converter, ESP32, and motor driver) are connected together for a common reference.

9. Upload the code to your ESP32 and enjoy!

  • Open your Arduino IDE or preferred coding platform.

  • Copy and paste the provided source code for gesture control and RGB direction indicators.

  • Select the correct ESP32 board and COM port, then upload the code.

  • Once uploaded, test the system by powering it on and using hand gestures to control the movement and LED indicators.

SOFTWARE SETUP

This is the Arduino sketch which will integrate the gesture sensor, RGB modules, 4-wheel drive motors and driver, to the ESP32 dec module. 

#include <Wire.h>
#include <SparkFun_APDS9960.h>

#define IN_A1 26
#define IN_A2 25
#define IN_B1 33
#define IN_B2 32

// RGB LED 1
#define RED_1 4
#define GREEN_1 15
#define BLUE_1 2

// RGB LED 2
#define RED_2 13
#define GREEN_2 23
#define BLUE_2 27

// RGB LED 3
#define RED_3 28
#define GREEN_3 30
#define BLUE_3 31

#define Speed 1200
#define Delay_Time 100

SparkFun_APDS9960 apds;

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

  // Motor pins
  pinMode(IN_A1, OUTPUT);
  pinMode(IN_A2, OUTPUT);
  pinMode(IN_B1, OUTPUT);
  pinMode(IN_B2, OUTPUT);

  // RGB LED pins
  pinMode(RED_1, OUTPUT);
  pinMode(GREEN_1, OUTPUT);
  pinMode(BLUE_1, OUTPUT);

  pinMode(RED_2, OUTPUT);
  pinMode(GREEN_2, OUTPUT);
  pinMode(BLUE_2, OUTPUT);

  pinMode(RED_3, OUTPUT);
  pinMode(GREEN_3, OUTPUT);
  pinMode(BLUE_3, OUTPUT);

  turnOffAll(); // Start with all LEDs off

  if (!apds.init()) {
    Serial.println("APDS-9960 initialization failed!");
    while (1);
  }
  Serial.println("APDS-9960 initialized!");

  if (!apds.enableGestureSensor(true)) {
    Serial.println("Failed to enable gesture sensor!");
    while (1);
  }
  Serial.println("Gesture sensor enabled!");
}

void loop() {
  if (apds.isGestureAvailable()) {
    int gesture = apds.readGesture();

    switch (gesture) {
      case DIR_UP: {
        Serial.println("UP");
        GREEN_LED();
        Move_Forward();
        delay(Speed);
        Motor_Stop();
        break;
      }

      case DIR_DOWN: {
        Serial.println("DOWN");
        BLUE_LED();
        Move_Backward();
        delay(Speed);
        Motor_Stop();
        break;
      }

      case DIR_LEFT: {
        Serial.println("LEFT");
        Turn_Left();
        unsigned long startLeft = millis();
        while (millis() - startLeft < Speed) {
          RunningLightLeft(200);
        }
        Motor_Stop();
        turnOffAll();
        break;
      }

      case DIR_RIGHT: {
        Serial.println("RIGHT");
        Turn_Right();
        unsigned long startRight = millis();
        while (millis() - startRight < Speed) {
          RunningLightRight(200);
        }
        Motor_Stop();
        turnOffAll();
        break;
      }

      case DIR_NEAR: {
        Serial.println("NEAR");
        break;
      }

      case DIR_FAR: {
        Serial.println("FAR");
        break;
      }

      default: {
        Serial.println("NONE");
        RED_LED();
      }
    }
  }

  ALTERNATE(Delay_Time); // Idle animation
}

// ==== Motor Functions ====

void Motor_Stop() {
  digitalWrite(IN_A1, LOW);
  digitalWrite(IN_A2, LOW);
  digitalWrite(IN_B1, LOW);
  digitalWrite(IN_B2, LOW);
}

void Move_Forward() {
  digitalWrite(IN_A1, HIGH);
  digitalWrite(IN_A2, LOW);
  digitalWrite(IN_B1, HIGH);
  digitalWrite(IN_B2, LOW);
}

void Move_Backward() {
  digitalWrite(IN_A1, LOW);
  digitalWrite(IN_A2, HIGH);
  digitalWrite(IN_B1, LOW);
  digitalWrite(IN_B2, HIGH);
}

void Turn_Left() {
  digitalWrite(IN_A1, HIGH);
  digitalWrite(IN_A2, LOW);
  digitalWrite(IN_B1, LOW);
  digitalWrite(IN_B2, HIGH);
}

void Turn_Right() {
  digitalWrite(IN_A1, LOW);
  digitalWrite(IN_A2, HIGH);
  digitalWrite(IN_B1, HIGH);
  digitalWrite(IN_B2, LOW);
}

// ==== LED Color Functions ====

void RED_LED() {
  digitalWrite(RED_3, LOW);
  digitalWrite(GREEN_3, HIGH);
  digitalWrite(BLUE_3, HIGH);
}

void GREEN_LED() {
  digitalWrite(RED_3, HIGH);
  digitalWrite(GREEN_3, LOW);
  digitalWrite(BLUE_3, HIGH);
}

void BLUE_LED() {
  digitalWrite(RED_3, HIGH);
  digitalWrite(GREEN_3, HIGH);
  digitalWrite(BLUE_3, LOW);
}

void ALTERNATE(int delayTime) {
  // Red
  digitalWrite(RED_3, LOW);
  digitalWrite(GREEN_3, HIGH);
  digitalWrite(BLUE_3, HIGH);
  delay(delayTime);

  // Green
  digitalWrite(RED_3, HIGH);
  digitalWrite(GREEN_3, LOW);
  digitalWrite(BLUE_3, HIGH);
  delay(delayTime);

  // Blue
  digitalWrite(RED_3, HIGH);
  digitalWrite(GREEN_3, HIGH);
  digitalWrite(BLUE_3, LOW);
  delay(delayTime);
}

// ==== Running Light Effects ====

void RunningLightLeft(int delayTime) {
  turnOffAll();
  // LED 3 ON
  digitalWrite(RED_3, LOW);
  digitalWrite(GREEN_3, LOW);
  digitalWrite(BLUE_3, HIGH);
  delay(delayTime);
  turnOffAll();

  // LED 2 ON
  digitalWrite(RED_2, LOW);
  digitalWrite(GREEN_2, LOW);
  digitalWrite(BLUE_2, HIGH);
  delay(delayTime);
  turnOffAll();

  // LED 1 ON
  digitalWrite(RED_1, LOW);
  digitalWrite(GREEN_1, LOW);
  digitalWrite(BLUE_1, HIGH);
  delay(delayTime);
  turnOffAll();
}

void RunningLightRight(int delayTime) {
  turnOffAll();
  // LED 1 ON
  digitalWrite(RED_1, LOW);
  digitalWrite(GREEN_1, LOW);
  digitalWrite(BLUE_1, HIGH);
  delay(delayTime);
  turnOffAll();

  // LED 2 ON
  digitalWrite(RED_2, LOW);
  digitalWrite(GREEN_2, LOW);
  digitalWrite(BLUE_2, HIGH);
  delay(delayTime);
  turnOffAll();

  // LED 3 ON
  digitalWrite(RED_3, LOW);
  digitalWrite(GREEN_3, LOW);
  digitalWrite(BLUE_3, HIGH);
  delay(delayTime);
  turnOffAll();
}

// ==== Utility ====

void turnOffAll() {
  digitalWrite(RED_1, HIGH);
  digitalWrite(GREEN_1, HIGH);
  digitalWrite(BLUE_1, HIGH);

  digitalWrite(RED_2, HIGH);
  digitalWrite(GREEN_2, HIGH);
  digitalWrite(BLUE_2, HIGH);

  digitalWrite(RED_3, HIGH);
  digitalWrite(GREEN_3, HIGH);
  digitalWrite(BLUE_3, HIGH);
}


CODE BREAKDOWN

What is code does?

  1. Detects gesture using APDS-9960 motion sensor.
  2. Controls motors to move forward, backward, left, or right depending on the gesture.
  3. Controls 3 RGB led's for visual effects
  •  
    • change colors
    • makes running light effects when turning left or right
  • First we include the necessary libraries. This allows ESP32 TO talk to the gesture sensor.

  #include <Wire.h>               // For I2C communication
  #include <SparkFun_APDS9960.h>  // Gesture sensor library

  • Define pins. These tells the ESP32 which pins are connect to motors and LED's.

#define IN_A1 26 // Motor A
#define IN_A2 25
#define IN_B1 33 // Motor B
#define IN_B2 32

// RGB LEDs (3 different LEDs, each has RED, GREEN, BLUE pins)
#define RED_1 4
#define GREEN_1 15
#define BLUE_1 2

  • Setups pins and initialized gesture sensor. Also stops the is the sensor is doesn't work.

void setup() {
  Serial.begin(115200); // For debugging messages
  Wire.begin();         // Start I2C communication

  // Set motor and LED pins as OUTPUT
  pinMode(IN_A1, OUTPUT);
  pinMode(RED_1, OUTPUT);
  // ... (rest of pins)

  turnOffAll(); // Turn off all LEDs at start

  // Initialize gesture sensor
  if (!apds.init()) {
    Serial.println("APDS-9960 failed!");
    while (1);
  }
  if (!apds.enableGestureSensor(true)) {
    Serial.println("Gesture sensor failed!");
    while (1);
  }
}

  •  Main loop. Where the sensors detects, moves the motors and light the RGB's.

void loop() {
  if (apds.isGestureAvailable()) {
    int gesture = apds.readGesture();

    switch (gesture) {
      case DIR_UP:    // Hand moves up
        GREEN_LED();
        Move_Forward();
        delay(Speed);
        Motor_Stop();
        break;

      case DIR_LEFT:  // Hand moves left
        Turn_Left();
        unsigned long startLeft = millis();
        while (millis() - startLeft < Speed) {
          RunningLightLeft(200); // LEDs run left
        }
        Motor_Stop();
        turnOffAll();
        break;

      case DIR_RIGHT: // Hand moves right
        Turn_Right();
        unsigned long startRight = millis();
        while (millis() - startRight < Speed) {
          RunningLightRight(200); // LEDs run right
        }
        Motor_Stop();
        turnOffAll();
        break;

      default:
        RED_LED(); // Default color
    }
  }
  ALTERNATE(Delay_Time); // Idle animation
}

  • Motor functions, LED functions, and Running light effect function.

void Move_Forward() { ... }    // Both wheels forward
void Turn_Left() { ... }       // Left turn
void Turn_Right() { ... }      // Right turn
void Motor_Stop() { ... }      // Stops all motors

void GREEN_LED() { ... }    // Show green on LED 3
void RED_LED() { ... }      // Show red on LED 3
void ALTERNATE() { ... }    // Change colors in sequence

void RunningLightLeft(int delayTime) {
  // Lights move from LED 3 LED 2 LED 1
}
void RunningLightRight(int delayTime) {
  // Lights move from LED 1 LED 2 LED 3
}

SUMMARY: 

  • setup(): Initializes motors, LEDs, and gesture sensor.
  • loop(): Watches for gestures. Moves motors & lights up LEDs.
  • Move_Forward, Turn_Left, etc.: Controls motor direction.
  • GREEN_LED, RED_LED, etc.: Lights up LEDs in color.
  • RunningLightLeft/Right(): Makes LED “run” left/right when turning.

 

VIDEO DEMONSTRATION

CONCLUSION

 

This project successfully demonstrates a gesture-controlled robotic system using the ESP32 microcontroller and the APDS-9960 gesture sensor. By waving your hand in different directions, you can intuitively control the movement of the motors (forward, backward, left, and right) and trigger visual LED effects that enhance user feedback. The integration of multiple RGB LEDs provides a more interactive and visually appealing experience, while the running light effect reinforces the robot’s turning direction. This system highlights the versatility of combining gesture recognition with motor and light control, making it a practical foundation for smart robotics applications.

Recommendation and  for future projects

  • Add Speed Control
    • Implement gesture-based speed adjustment (e.g., hand near = slow, hand far = fast).
    • Alternatively, use potentiometers or sliders for precise control.
  • Obstacle Avoidance
    • Integrate ultrasonic or infrared sensors to detect obstacles and prevent collisions.
  • Bluetooth/Wi-Fi Connectivity
    • Add wireless control using a smartphone app or voice commands for remote operation.
  • Battery Monitoring
    • Display battery level using LEDs or send warnings over serial/Bluetooth when power is low.
  • Improved Lighting Effects
    • Use PWM control for smooth LED color transitions and breathing effects.
    • Program more advanced light patterns like rainbow cycling or flashing indicators for different gestures.
  • Mechanical Enhancements
    • Upgrade to servo motors for more precise movement.
    • Use a stronger chassis to carry additional payloads or sensors.
  • AI Integration
    • Use machine learning for gesture classification beyond the APDS-9960's basic gestures.


REFERENCES

  • REFERENCES

    1. SparkFun APDS-9960 Library Documentation
      https://github.com/sparkfun/SparkFun_APDS-9960_RGB_and_Gesture_Sensor_Library
    2. ESP32 Technical Reference Manual
      https://www.espressif.com/sites/default/files/documentation/esp32_technical_reference_manual_en.pdf
    3. Arduino Reference – pinMode(), digitalWrite(), delay()
      https://www.arduino.cc/reference/en/
    4. Wire Library (I2C Communication)
      https://www.arduino.cc/en/Reference/Wire
    5. Gesture Recognition Sensor – APDS-9960 Datasheet
      https://cdn.sparkfun.com/datasheets/Sensors/Proximity/APDS9960.pdf
Esp32MotionMotion detectionMotion detectorRgbRobot car kitRoboticsSmart robot car

Leave a comment

All comments are moderated before being published