A simulation project of a planar bipedal robot designed to explore dynamic walking and balance control within the MuJoCo physics engine. The project focuses on implementing robust, purely mathematical, closed-loop controllers to achieve standing stability and steady gait generation.
Unlike many modern approaches that rely on Machine Learning, the current project utilizes classical control theory, specifically the Linear Inverted Pendulum Model (LIPM) and Instantaneous Capture Point (ICP) logic to achieve locomotion. The robot is based on the walker2d MuJoCo model, restricted to the sagittal plane (2D) to focus on the fundamental physics of forward balance and walking.
The software architecture strictly separates high-level gait planning from low-level joint control:
walker2d_biped_project/
├── main.py # Main simulation loop
├── config.py # Centralized parameters and physical constants
├── controller/ # Robot's brain and control logic
│ ├── ik_solver.py # 2D Inverse Kinematics (Human-like kinematics)
│ ├── fsm.py # Gait Finite State Machine (ICP Planner)
| ├── push_recovery.py
│ └── standing.py # State Estimator and Balance Controller
└── models/ # MuJoCo XML definitions
├── scene.xml # World environment (floor, lighting)
└── walker2d.xml # Robot kinematics and actuators
This project requires Python 3.8+ and the following core libraries:
mujoco: The official Python bindings for the MuJoCo physics engine.numpy: Used for matrix operations, vector math, and state arrays.matplotlib: Used for rendering the 2D telemetry dashboard and 3D trajectory plots.
Install all required dependencies using pip:
pip install mujoco numpy matplotlibThe workflow is split into two steps to ensure maximum simulation performance without the overhead of real-time plotting:
- Run the Simulation Execute the main script to launch the MuJoCo passive viewer. The robot will automatically progress through Standing (Task 1), Walking (Task 2), and the Phase-Locked Push Recovery stress test (Task 3).
python main.py- View Telemetry & Kinematics Once the simulation finishes and the data file is saved, run the plotter to generate the 2D analytics dashboard and the separate 3D trajectory graph:
python plot_sim_data.pyTo maintain an upright posture, the robot utilizes a centralized active balance strategy.
-
Static Equilibrium: The ankle joint in the
walker2dmodel is located at the heel. To center the Center of Mass (CoM) over the foot, a nominal offset of -0.10m is applied (NOM_FOOT_X = -0.10). -
Torso Stabilization: A PD controller monitors the torso's pitch angle and angular velocity. The resulting correction (
$\Delta p$ ) is applied to the hips to fight gravity and keep the spine vertical. -
Anti-Lever Logic: To keep the feet flat while the hips correct the torso, the correction
$\Delta p$ is mathematically subtracted from the ankle targets.
Walking is treated as a "controlled fall" where the robot places its feet to "catch" its falling Center of Mass.
-
Gait Cycle: Controlled by
fsm.py, alternating between Double Support and Single Support (Swing) phases. -
Capture Point Logic: For every step, the FSM calculates the target world position (
$Target_{world}$ ) based on the current CoM velocity ($v$ ) and a target velocity ($v_{target}$ ):$$Target_{world} = CoM_x + \frac{v \cdot T_{step}}{2} + K_v(v - v_{target})$$ -
Execution: The foot position is interpolated using a sinusoidal trajectory for height (
SWING_DZ). -
Actuator Strategy: To facilitate the fall, the ankles use low gains (
$K_p = 60$ ), while the hips and knees use high gains ($K_p = 500$ ) to support the body weight.
Push recovery is implemented as a closed-loop step adjustment problem. The controller computes the sagittal Instantaneous Capture Point:
where
The recovery term is clipped by the leg reach limits (DX_MAX), and emergency pushes can trigger shorter step times or recovery stances.
The joints are controlled via a custom Proportional-Derivative (PD) loop in main.py, simulating virtual springs and dampers:
-
$K_p$ (Proportional): Defines the stiffness of the "spring." High$K_p$ (e.g., 500) creates a rigid leg. -
$K_d$ (Derivative): Defines the damping. It prevents high-frequency oscillations and ensures smooth ground contact.
The ik_solver.py converts Cartesian