This work presents the development of a simulated quadruped locomotion system controlled through Model Predictive Control. To formulate the problem as a convex Quadratic Program suitable for MPC, several simplifying assumptions were introduced to approximate the robot’s dynamics. Simulations were performed using the Lite3 quadruped robot from DeepRobotics. A dedicated footstep planner, along with ground and swing leg controllers, was implemented and kept as simple as possible to reduce the overall complexity of the work while maintaining effective locomotion behavior. The simulation results demonstrate that the MPC framework can successfully control quadruped walking. Various gaits were tested under different conditions, showing that the controller is robust and capable of achieving stable and accurate locomotion.
Trotting | Pronking |
---|---|
![]() |
![]() |
Ambling | Galopping |
---|---|
![]() |
![]() |
.
├── lite3_urdf/ # URDF model of the Lite3 robot
├── presentation/
├── UR_presentation # Presentation of the project
├── UR_report.pdf # Detailed report of the project
├── UR_paper.pdf # Reference paper
├── src/
├── main.py # Runnable: Main entry point for simulation
├── plot.py # Runnable: Plot some data decided into the script
├── foot_trajectory_generator.py # Swing trajectory generation
├── footstep_planner.py # Main footstep planner script
├── mpc.py # MPC optimization logic
├── utils.py # Utility functions
├── logger.py # Logging utilities
├── README.md # Project documentation
The footstep planner is based on a virtual unicycle model located under the robot's center of mass (CoM). Foot placements are computed by integrating a constant reference velocity
The unicycle motion evolves as:
This strategy allows generating different gait patterns by defining alternating support and swing phases for the legs.
Swing trajectories are generated using polynomial interpolation:
- Cubic interpolation in the horizontal plane:
- Quartic interpolation for the vertical (z) axis:
with coefficients:
These trajectories ensure smooth lift-off and landing with zero velocity and acceleration at boundaries.
The MPC computes optimal ground reaction forces over a finite time horizon using a simplified rigid-body model. It enforces dynamic feasibility, swing/stance contact constraints, and friction cone conditions.
The ground controller transforms the optimal ground reaction force
Where:
-
$J_i$ is the foot Jacobian, -
$R_i$ is the rotation from robot to world frame, -
$\tau_i$ is the joint torque vector.
The swing controller combines feedback and feedforward terms to track the foot trajectory:
Where the feedforward torque is:
This ensures smooth and accurate motion tracking during the swing phase.
- Occasional ground penetration, problem arise in simulation side
- Visual meshes for the robot had to be manually rotated to ensure proper visualization in simulation.
- Required libraries are: numpy, matplotlib, osqp, dartpy
- Runnable scripts are: main.py, plot.py
- Press space bar to start the simulation
- Di Carlo et al. (2018). Dynamic Locomotion in the MIT Cheetah 3 Through Convex Model-Predictive Control. IEEE/RSJ IROS, Madrid, Spain.
- Stark et al. (2025). Benchmarking Different QP Formulations and Solvers for Dynamic Quadrupedal Walking. arXiv:2502.01329v1 [cs.RO]
- Zhu (GitHub). Lite 3 URDF Configuration. TopHillRobotics Repository
- Reference for implementation: DIAG-Robotics-Lab/ismpc
Vittorio Pisapia(VittorioPisapia), Jacopo Tedeschi(jacopotdsc), Emiliano Paradiso(Emilianogith), Brian Piccione(HatoKng)