Spider Robot DIY Wireless Quadruped - MicroROS Balance Controller

by xprobyhimself in Circuits > Robots

0 Views, 0 Favorites, 0 Comments

Spider Robot DIY Wireless Quadruped - MicroROS Balance Controller

Untitled design (1).png
Spider Robot DIY Quadruped V2 Wireless - MicroROS Balance Controller
Self-balancing Spider Robot
Spider Robot DIY Quadruped V2 Wireless

An advanced upgrade to the Spider Robot with ROS2, MicroROS, and self-balancing capabilities!

Taking Your Spider Robot to the Next Level

Remember the simple spider robot we built before? Well, it's time to give it superpowers!

This Version 2 upgrade transforms your basic quadruped into an intelligent, self-balancing robot powered by ROS2 and micro-ROS. Think of it as giving your robot a brain upgrade—it can now sense its orientation, automatically correct its balance, and communicate wirelessly with a powerful ROS2 system on your computer.

What makes this exciting? Your robot will use an MPU6050 gyroscope/accelerometer to sense when it's tilting, and then automatically adjust its legs to stay balanced. Plus, you'll have a beautiful GUI (graphical interface) on your computer to monitor everything in real-time and tune the robot's behavior. It's like having mission control for your spider robot!

Don't worry if you haven't worked with ROS2 before - I'll walk you through everything step by step. By the end of this tutorial, you'll have a robot that's not just cool to look at, but actually smart enough to maintain its balance on uneven surfaces.

Supplies

F03R8J1MKHYP4B7.png
FPKPG0QMKHYP4BI.jpg
F6DGWECMKHYP500.jpg

What You'll Need

Hardware (Same as V1, plus new components)

From the Original Build:

  1. 8x Micro Servo SG90 motors
  2. ESP32 or ESP8266 board (ESP32 recommended for this version)
  3. PCA9685 Servo Driver
  4. 3.7V LiPo battery (2500mAh or higher recommended)
  5. All the 3D printed parts from Version 1
  6. Jumper wires

New Components for V2:

  1. MPU6050 Gyroscope/Accelerometer Module (around $3-5 online)
  2. 4x additional jumper wires for MPU6050 connection
  3. Micro USB cable for programming
  4. A computer running Ubuntu 22.04 (for ROS2)

Software Requirements

  1. Arduino IDE (1.8.x or 2.x)
  2. ROS2 Humble or Jazzy (we'll install this together)
  3. Python 3.8 or higher
  4. Git (for cloning the repository)

Don't have Ubuntu? You can use:

  1. Windows with WSL2 (Windows Subsystem for Linux)
  2. A virtual machine running Ubuntu

Wiring the MPU6050 Sensor

F7IVJN8MKHYP7LR.png
FZFPB0CMKHYP7MV.png

The MPU6050 is your robot's inner ear - it senses which way is up and detects any tilting. Let's connect it to your ESP32.

Understanding the MPU6050 Pins

Your MPU6050 module has these pins:

  1. VCC: Power input (3.3V)
  2. GND: Ground
  3. SCL: Serial Clock Line (for I2C communication)
  4. SDA: Serial Data Line (for I2C communication)
  5. INT: Interrupt pin (we won't use this)
  6. AD0: Address select (we won't use this)

Wiring Diagram

Connect the MPU6050 to your ESP32 like this:
MPU6050 → ESP32
────────────────────────────
VCC (3.3V) → 3.3V
GND → GND
SCL → GPIO 33 (SCL)
SDA → GPIO 32 (SDA)

Important Notes:

  1. Use 3.3V, NOT 5V! The MPU6050 can be damaged by 5V (Not really but don't )
  2. Double-check your connections before powering on

Updated Complete Wiring (ESP32 → Everything)

ESP32 → PCA9685:

ESP32 → PCA9685
────────────────────────────
GPIO 22 (SCL) → SCL
GPIO 21 (SDA) → SDA
3.3V → VCC
GND → GND

ESP32 → MPU6050:

ESP32 → MPU6050
────────────────────────────
GPIO 33 (SCL) → SCL
GPIO 32 (SDA) → SDA
3.3V → VCC
GND → GND

Battery:

  1. Battery positive → PCA9685 V+
  2. Battery negative → PCA9685 GND (and ESP32 GND)

NOTICE: You can use the ESP32 as the "brain" with two I2C devices (PCA9685 and MPU6050) sharing the same I2C bus (GPIO 21 and 22). The PCA9685 then controls all 8 servos with simple changes in code.


Install ROS 2 on Your PC

FZERRQGMKHYPYVG.png
FN20YU4MKHYPYVH.png
  1. Set locale:
sudo apt update && sudo apt install locales
sudo locale-gen en_US en_US.UTF-8
sudo update-locale LC_ALL=en_US.UTF-8 LANG=en_US.UTF-8
export LANG=en_US.UTF-8
  1. Add ROS 2 repo (for Jazzy on Ubuntu 24.04; replace jazzy with humble for 22.04):
sudo apt install software-properties-common
sudo add-apt-repository universe
sudo apt update && sudo apt install curl
sudo curl -sSL https://raw.githubusercontent.com/ros/rosdistro/master/ros.key -o /usr/share/keyrings/ros-archive-keyring.gpg
echo "deb [arch=$(dpkg --print-architecture) signed-by=/usr/share/keyrings/ros-archive-keyring.gpg] http://packages.ros.org/ros2/ubuntu $(. /etc/os/release && echo $UBUNTU_CODENAME) main" | sudo tee /etc/apt/sources.list.d/ros2.list > /dev/null
  1. Install ROS 2:
sudo apt update
sudo apt install ros-jazzy-desktop python3-colcon-common-extensions
  1. Source it (add to ~/.bashrc):
source /opt/ros/jazzy/setup.bash
  1. Install additional packages from the repo:
pip3 install matplotlib numpy
sudo apt install python3-tk python3-rclpy python3-std-msgs




Set Up the Quadruped Controller on PC

F009FZAMKHYQ04H.png
FZTH4DFMKHYQ03F.png
FRFLVQJMKHYQ03G.png
  1. Clone the repo:
git clone https://github.com/ReizarXPro/MicroRos-Spider-Robot-Balance-controller-quadrupedV2-.git
cd MicroRos-Spider-Robot-Balance-controller-quadrupedV2-/quadruped_controller2
  1. Make launch script executable (if present):
chmod +x launch.sh
./launch.sh
  1. Or manually:
  2. Terminal 1: python3 quadruped_balance_controller_pid.py
  3. Terminal 2: python3 quadruped_gui.py (Source ROS 2 in each terminal first.)


Install Micro-ROS Tools on PC

  1. Install micro-ROS agent:
sudo apt install ros-jazzy-micro-ros-agent

Set Up Micro-ROS Firmware on ESP32 (Using PlatformIO – Easiest Method)

  1. Install VS Code + PlatformIO extension (or use CLI).
  2. Create new PlatformIO project:
  3. Board: ESP32 Dev Module
  4. Framework: Arduino
  5. Edit platformio.ini:


[env:esp32doit-devkit-v1]
platform = espressif32
board = esp32doit-devkit-v1
framework = arduino
monitor_speed = 115200
board_microros_transport = wifi

lib_deps =
https://github.com/micro-ROS/micro_ros_platformio
adafruit/Adafruit PWM Servo Driver Library@^3.0.1
electroniccats/mpu6050@^1.0.0

build_flags =
-D MICRO_ROS_TRANSPORT_ARDUINO_WIFI


Replace src/main.cpp with custom Micro-ROS code (basic example below – adjust pins, WiFi, servo mapping):

#include <Arduino.h>
#include <micro_ros_platformio.h>
#include <WiFi.h>
#include <std_msgs/msg/float32_multi_array.h>
#include <std_msgs/msg/int32_multi_array.h>
#include <Adafruit_MPU6050.h>
#include <Adafruit_Sensor.h>
#include <ESP32Servo.h>

// WiFi settings (for UDP transport)
const char* ssid = "YOUR_SSID";
const char* password = "YOUR_PASSWORD";
// Agent IP and port (PC running agent)
IPAddress agent_ip(192, 168, 1, 100); // Change to your PC IP
uint16_t agent_port = 8888;

Adafruit_MPU6050 mpu;
Servo servos[8];
int servo_pins[8] = {13, 12, 14, 27, 26, 25, 33, 32}; // Adjust to your wiring

rcl_publisher_t imu_publisher;
std_msgs__msg__Float32MultiArray imu_msg;
rcl_subscription_t servo_subscriber;
std_msgs__msg__Int32MultiArray servo_msg;

void servo_callback(const void* msgin) {
const std_msgs__msg__Int32MultiArray* msg = (const std_msgs__msg__Int32MultiArray*)msgin;
for (int i = 0; i < 8; i++) {
servos[i].write(msg->data.data[i]);
}
}

void setup() {
Serial.begin(115200);
WiFi.begin(ssid, password);
while (WiFi.status() != WL_CONNECTED) delay(500);

set_microros_wifi_transports(ssid, password, agent_ip, agent_port);

// Init MPU6050
mpu.begin();
mpu.setAccelerometerRange(MPU6050_RANGE_8_G);
mpu.setGyroRange(MPU6050_RANGE_500_DEG);
mpu.setFilterBandwidth(MPU6050_BAND_21_HZ);

// Init servos
for (int i = 0; i < 8; i++) {
servos[i].attach(servo_pins[i]);
}

// Micro-ROS init (allocators, node, publisher/subscriber)
// Follow standard micro_ros_platformio examples for full init code
}

void loop() {
if (rclc_executor_spin_some(&executor, RCL_MS_TO_NS(100)) != RCL_RET_OK) return;

sensors_event_t a, g, temp;
mpu.getEvent(&a, &g, &temp);

float data[7] = {a.acceleration.x, a.acceleration.y, a.acceleration.z,
g.gyro.x, g.gyro.y, g.gyro.z, temp.temperature};
std_msgs__msg__Float32MultiArray__init(&imu_msg);
imu_msg.data.data = data;
imu_msg.data.size = 7;
imu_msg.data.capacity = 7;
rcl_publish(&imu_publisher, &imu_msg, NULL);
}


Run the System

FQYZP68MKHYQ4G2.png
F2ROHGNMKCUNP71.png
FWQP2DOMKCUNP72.png
FYUK5F6MKCUNP7D.png
FMNCZJIMKHYQ4GR.png
  1. On PC – start micro-ROS agent (UDP example):
ros2 run micro_ros_agent micro_ros_agent udp4 --port 8888

Launching the GUI

Now for the fun part - the graphical control interface!

Using the Launch Script (Easiest)

The launch.sh script makes everything simple:cd ~/spider_robot_v2/quadruped_controller2


cd ~/spider_robot_v2/quadruped_controller2
./launch.sh

You'll see a menu:

╔══════════════════════════════════════════════╗
║ Spider Robot V2 - Launch Menu ║
╚══════════════════════════════════════════════╝

1) Start Controller Only
2) Start GUI Only
3) Start Both (Recommended)
4) Stop All
5) Exit

Select option [1-5]:

Choose option 3 - this will start both the controller and GUI.

First Time Setup

When you first open the GUI:

  1. Place robot on a flat surface
  2. Click "Calibrate Gyroscope" - wait 2 seconds
  3. Click "Calibrate Accelerometer" - wait 2 seconds
  4. Watch the attitude graphs - they should stabilize near 0°


Understanding the ROS2 Topics

Spider Robot DIY Quadruped V2 Wireless
F8CNPVAMKHYQ1Q6.png

Let's learn about how the data flows through the system. This will help you debug issues and extend the project.

Topic Architecture

Your system has two main topics:

1. /esp32/mpu6050/data (Publisher: ESP32 → Subscriber: Computer)

  1. Type: std_msgs/Float32MultiArray
  2. Frequency: 50 Hz (20ms interval)
  3. Data: [accel_x, accel_y, accel_z, gyro_x, gyro_y, gyro_z, temperature]

2. /esp32/servo/angles (Publisher: Computer → Subscriber: ESP32)

  1. Type: std_msgs/Int32MultiArray
  2. Frequency: 50 Hz
  3. Data: [servo0, servo1, servo2, servo3, servo4, servo5, servo6, servo7]

Monitoring Topics in Real-Time

See all topics:

ros2 topic list

Watch IMU data:

ros2 topic echo /esp32/mpu6050/data

Watch servo commands:

ros2 topic echo /esp32/servo/angles

Check message frequency:

ros2 topic hz /esp32/mpu6050/data

You should see around 50 Hz.

Check if anyone is listening:

ros2 topic info /esp32/mpu6050/data

Recording and Playback (Advanced)

You can record your robot's behavior for analysis:

Record data:

ros2 bag record /esp32/mpu6050/data /esp32/servo/angles

Play it back later:

ros2 bag play <your_bag_file>

Why this is useful:

  1. Debug issues by reviewing recorded data
  2. Compare different PID settings
  3. Share your robot's behavior with others
  4. Analyze performance without the robot

Enjoy your balancing spider robot! If you hit issues, share error messages. 🤖


Downloads