← Back to projects

Robot Dog

Custom quadruped robot for autonomous indoor navigation with ROS2 control system

2024ros2, robotics, simulation, control-systems

View on GitHub


The Problem

Building a quadruped robot from scratch requires solving multiple interconnected challenges: mechanical design, control algorithms, simulation, and hardware integration. The primary goal was to create an autonomous robot dog capable of indoor navigation, but we needed a development workflow that wouldn't risk damaging expensive hardware during algorithm development.

The challenge: Develop control algorithms and test them safely before deploying on physical hardware, while maintaining modularity between simulation and real robot.


System Architecture

High-Level Design

[Control Algorithms] --ROS2--> [Simulation/Hardware Bridge] --> [Physical Robot]
                                          |
                                          v
                                     [PyBullet Sim]

Key design principle: Use ROS2 as the abstraction layer between control algorithms and hardware. This allows the same control code to run on simulation or physical robot with minimal changes.

Software Stack

robot_ws/
├── robot_sim/          # PyBullet simulation node
├── robot_control/      # Gait generation, IK/FK
├── robot_hardware/     # STM32 firmware interface
└── robot_nav/          # Localization and navigation (planned)

Simulation Development Journey

Phase 1: Matplotlib Stick Figure

Why start simple? Before investing in complex physics simulation, we needed to verify our inverse kinematics (IK) calculations were correct.

Implementation:

Created a simple 2D stick-figure model directly from Fusion360 measurements:

def draw_leg(ax, base_pos, joint_angles):
    """Draw leg based on joint angles."""
    # Forward kinematics
    hip_pos = base_pos + [cos(joint_angles[0]) * L1, sin(joint_angles[0]) * L1]
    knee_pos = hip_pos + [cos(joint_angles[0] + joint_angles[1]) * L2, ...]
    foot_pos = knee_pos + [cos(sum(joint_angles)) * L3, ...]
ax.plot([base_pos[0], hip_pos[0], knee_pos[0], foot_pos[0]], 
        [base_pos[1], hip_pos[1], knee_pos[1], foot_pos[1]], 'b-o')

Validation process:

  • Command specific joint angles on physical robot
  • Measure foot position with calipers
  • Compare to Matplotlib model output
  • Iterate until IK matches reality

Result: Found and fixed several IK errors before moving to 3D simulation.

Phase 2: Gazebo + ROS2 (The Struggle)

Why Gazebo? Industry standard for ROS2, extensive documentation, physics-based simulation.

Challenge 1: URDF Closed Chain Problem

Our robot uses a closed-chain leg design (3DOF leg with parallel linkages). URDF enforces a tree structure (single parent per link), so closed chains aren't directly supported.

Options considered:

ApproachProsConsDecision
Open chain URDF + software closureAccurate dynamics, collision detectionComplex transforms from Fusion360Selected
Simplified open chainSimple, fastLess accurate dynamicsUsed initially
Custom physics engineFull controlMassive development timeRejected

Implementation: Created simplified open-chain URDF, then software mapper:

def servo_to_urdf_joints(servo_angles):
    """Map servo joint angles to URDF model joint angles."""
    # Forward kinematics of closed chain leg
    foot_pos = closed_chain_fk(servo_angles)
    # Inverse kinematics of open chain URDF leg
    urdf_angles = open_chain_ik(foot_pos)
    return urdf_angles

Challenge 2: ROS2 Control Issues

After hours of tuning Gazebo parameters and inertia tensors, we got the robot standing. Then we tried to control it with ros2-control...

The problem: ROS2 control doesn't handle legged robots well. The robot would:

  • Skid and slide
  • Build up acceleration
  • Become unstable

Root cause: ROS2 control is designed for manipulators (serial chains), not dynamic legged systems. The control framework assumes quasi-static operation, which doesn't hold for quadrupeds.

Decision: Abandon ros2-control for legged robot. Write custom controller or switch simulation engines.

Phase 3: PyBullet (The Solution)

Why PyBullet?

  • Easier setup — Load URDF directly, no complex configuration
  • Better for legged robots — Used by many quadruped research projects
  • Python API — Easier integration with ROS2 nodes
  • Fast iteration — Less time debugging simulation, more time on control

Architecture:

class RobotSimNode(Node):
    def __init__(self):
        super().__init__('robot_sim')
        # Initialize PyBullet
        self.physics_client = p.connect(p.GUI)
        self.robot = p.loadURDF("robot.urdf")
# ROS2 interfaces
self.joint_cmd_sub = self.create_subscription(
    JointState, 'joint_commands', self.joint_cmd_callback, 10)
self.robot_state_pub = self.create_publisher(
    JointState, 'robot_state', 10)
def joint_cmd_callback(self, msg):
    # Apply joint commands to PyBullet
    for i, joint_name in enumerate(msg.name):
        joint_idx = self.get_joint_index(joint_name)
        p.setJointMotorControl2(
            self.robot, joint_idx, 
            p.POSITION_CONTROL, 
            targetPosition=msg.position[i])

Hardware interface abstraction:

To maintain compatibility between sim and hardware, we created a control node that handles IK/FK mapping:

class ControlNode(Node):
    def servo_cmd_callback(self, msg):
        """Convert servo commands to URDF joint angles."""
        # Forward kinematics of closed-chain leg
        foot_positions = []
        for leg in self.legs:
            foot_pos = closed_chain_fk(leg.servo_angles)
            foot_positions.append(foot_pos)
# Inverse kinematics for URDF model
urdf_joint_angles = []
for foot_pos in foot_positions:
    angles = open_chain_ik(foot_pos)
    urdf_joint_angles.extend(angles)
# Publish to simulation
self.publish_joint_commands(urdf_joint_angles)

Control Algorithms

Gait Generation Philosophy

The control system is designed to be modular—different gait algorithms can be swapped without changing the hardware interface. This allows experimentation from simple open-loop gaits to advanced MPC/RL approaches.

Walk Gait

Pattern: One leg lifted at a time, other three legs move backward (stance phase).

Implementation:

def walk_gait(t, period=2.0):
    """Generate walk gait foot trajectories."""
    # Phase offset: each leg starts at different time
    phases = [0, period/4, period/2, 3*period/4]
for leg_idx, phase in enumerate(phases):
    leg_time = (t + phase) % period
if leg_time < period * 0.5:  # Swing phase
    # Lift leg, move forward
    z = swing_height * sin(leg_time / (period * 0.5) * pi)
    x = swing_distance * (leg_time / (period * 0.5))
else:  # Stance phase
    # Move backward while in contact
    z = 0
    x = -stance_distance * ((leg_time - period * 0.5) / (period * 0.5))
foot_targets[leg_idx] = [x, 0, z]

Characteristics:

  • Stable (always 3 legs on ground)
  • Slow
  • Good for precise movement

Trot Gait

Pattern: Diagonal legs in phase, diagonal pairs out of phase by 180°.

Implementation:

def trot_gait(t, period=1.0):
    """Generate trot gait foot trajectories."""
    # Diagonal pairs
    front_left_phase = 0
    back_right_phase = 0  # Same phase
    front_right_phase = period / 2
    back_left_phase = period / 2  # Out of phase
for leg_idx, phase in enumerate([front_left_phase, front_right_phase, 
                                 back_left_phase, back_right_phase]):
    leg_time = (t + phase) % period
if leg_time < period * 0.5:  # Swing
    z = swing_height * sin(leg_time / (period * 0.5) * pi)
    x = swing_distance * (leg_time / (period * 0.5))
else:  # Stance
    z = 0
    x = -stance_distance * ((leg_time - period * 0.5) / (period * 0.5))
foot_targets[leg_idx] = [x, 0, z]

Characteristics:

  • Fast
  • Dynamic (only 2 legs on ground at times)
  • Requires balance control (future work)

Hardware Design

Custom Controller Board

Requirements:

  • STM32 MCU for low-level motor control
  • IMU for orientation sensing
  • Power management
  • Communication interface (UART/SPI to main computer)

Design decisions:

ComponentChoiceRationale
MCUSTM32F4 seriesFast enough for servo control, good peripheral set
IMUMPU6050 or better6-DOF, common in robotics
CommunicationUARTSimple, reliable, sufficient bandwidth
PowerSeparate 5V/12V railsServos need 5V, MCU needs 3.3V

Status: Currently in design phase. Using off-the-shelf components for initial development.


Key Engineering Decisions

Decision 1: Simulation-First Development

Rationale:

  • Protect expensive hardware during algorithm development
  • Faster iteration (no physical setup time)
  • Test edge cases safely

Trade-off: Simulation never perfectly matches reality. Need validation on physical robot.

Decision 2: ROS2 for Abstraction

Rationale:

  • Industry standard for robotics
  • Modular architecture (nodes can be swapped)
  • Rich ecosystem of tools (rviz, foxglove)

Trade-off: Learning curve, but pays off in modularity.

Decision 3: Simplified URDF Model

Rationale:

  • Faster to implement
  • Good enough for control algorithm development
  • Can upgrade to closed-chain model later

Trade-off: Less accurate dynamics, but acceptable for gait development.

Decision 4: PyBullet over Gazebo

Rationale:

  • Better suited for legged robots
  • Easier setup and debugging
  • Python API integrates well with ROS2

Trade-off: Less ROS2-native, but worth it for development speed.


Lessons Learned

What Worked Well

  • Matplotlib validation — Catching IK errors early saved significant time
  • ROS2 modularity — Easy to swap simulation/hardware interfaces
  • PyBullet — Much faster iteration than Gazebo
  • Incremental complexity — Starting simple, adding complexity gradually

What I'd Improve

  • Closed-chain URDF from start — Would provide more accurate simulation
  • Better documentation — ROS2 setup can be confusing for newcomers
  • Automated testing — Unit tests for IK/FK functions
  • Hardware-in-the-loop — Earlier integration with physical robot

Key Insights

  • Simulation is never perfect — But it's invaluable for rapid development
  • Tool choice matters — Gazebo wasn't right for legged robots, PyBullet was
  • Modularity pays off — ROS2 abstraction allows easy swapping of components
  • Start simple — Matplotlib model caught errors before complex simulation

Technical Specifications

ComponentSpecification
Robot TypeQuadruped (4 legs)
Leg DOF3 per leg (closed chain)
Total Actuators12 servos
SimulationPyBullet
Control FrameworkROS2 (Humble)
Programming LanguagePython (control), C++ (firmware planned)
ControllerSTM32 (custom board in design)
SensorsIMU (planned)

Current Status and Future Work

Completed

  • ✅ Matplotlib validation model
  • ✅ PyBullet simulation integration
  • ✅ ROS2 control framework
  • ✅ Basic gait generation (walk, trot)
  • ✅ IK/FK implementation
  • ✅ Hardware abstraction layer

In Progress

  • 🔄 Custom STM32 controller board design
  • 🔄 IMU integration for balance control
  • 🔄 Closed-loop gait stabilization

Future Work

  • 📋 Closed-chain URDF model
  • 📋 MPC-based control
  • 📋 Reinforcement learning for gait optimization
  • 📋 Localization and navigation stack
  • 📋 Obstacle avoidance

Conclusion

This project demonstrates the importance of choosing the right tools for the job. Gazebo seemed like the obvious choice for ROS2, but it wasn't suited for legged robots. Switching to PyBullet accelerated development significantly.

The modular ROS2 architecture has proven valuable—we can develop control algorithms in simulation, then deploy to hardware with minimal changes. The abstraction layer between control and hardware is paying dividends as we iterate on algorithms.

Most importantly, this project reinforced that complex systems require incremental development. Starting with a simple Matplotlib model to validate IK, then moving to physics simulation, then adding control algorithms—each step built on the previous one. This approach caught errors early and maintained momentum throughout development.

The robot dog is still a work in progress, but the foundation is solid. The simulation framework allows rapid algorithm development, and the modular architecture will support future enhancements like MPC control and navigation.